diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp index f8bff21488c692f62d14463219ca1786338acb72..602f13fff37affd25ff664d3d8326d3d0f1beba4 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletEngine.cpp @@ -169,8 +169,8 @@ void BulletEngine::createFloorPlane( const Eigen::Vector3f &pos, const Eigen::Ve { boost::recursive_mutex::scoped_lock scoped_lock(engineMutex); DynamicsEngine::createFloorPlane(pos,up); - float size = 100000.0f; // mm - float sizeSmall = 1000.0f; + float size = 50000.0f; // mm + float sizeSmall = 500.0f; float w = size; float h = size; float d = sizeSmall; @@ -185,7 +185,10 @@ void BulletEngine::createFloorPlane( const Eigen::Vector3f &pos, const Eigen::Ve h = sizeSmall; d = size; } - groundObject = VirtualRobot::Obstacle::createBox(w,h,d); + + groundObject = VirtualRobot::Obstacle::createBox(w,h,d,VirtualRobot::VisualizationFactory::Color::Gray()); + std::string name("Floor"); + groundObject->setName(name); Eigen::Matrix4f gp; gp.setIdentity(); gp(2,3) = -sizeSmall*0.5f; diff --git a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp index b7609d234a7ea09991319390e34dfa570baed29f..1f20e9d230ea8377650143d24f9b4a2da03ca292 100644 --- a/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp +++ b/SimDynamics/DynamicsEngine/BulletEngine/BulletRobot.cpp @@ -905,8 +905,10 @@ void BulletRobot::actuateJoints(float dt) while (it!=actuationTargets.end()) { - BulletObjectPtr drn = boost::dynamic_pointer_cast<BulletObject>(it->second.dynNode); - VR_ASSERT(drn); + //BulletObjectPtr drn; + //if (it->second.dynNode) + // drn = boost::dynamic_pointer_cast<BulletObject>(it->second.dynNode); + //VR_ASSERT(drn); if (it->second.node->isRotationalJoint()) { LinkInfo link = getLink(it->second.node); diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp index b4390815f70a762dce3ffa563a6b2900e09db587..e0c241b70321cfdfb0376022acdcac2bf2802b70 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.cpp +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.cpp @@ -74,16 +74,18 @@ void DynamicsRobot::actuateNode( VirtualRobot::RobotNodePtr node, float jointVal VR_ASSERT(node); VR_ASSERT(robot->hasRobotNode(node)); - if (!hasDynamicsRobotNode(node)) - createDynamicsNode(node); + // if node is a joint without model, there is no dyn node! + //DynamicsObjectPtr dnyRN; + //if (hasDynamicsRobotNode(node)) + // dnyRN = getDynamicsRobotNode(node); + // createDynamicsNode(node); - DynamicsObjectPtr dnyRN = getDynamicsRobotNode(node); robotNodeActuationTarget target; target.enabled = true; target.node = node; target.jointValueTarget = jointValue; - target.dynNode = dnyRN; + //target.dynNode = dnyRN; actuationTargets[node] = target; } diff --git a/SimDynamics/DynamicsEngine/DynamicsRobot.h b/SimDynamics/DynamicsEngine/DynamicsRobot.h index 11b12eafebef1b117ffbeff9f803bc20635e2849..7f3b47fd62fcb9fb83bd4b0eca88c10f5447528d 100644 --- a/SimDynamics/DynamicsEngine/DynamicsRobot.h +++ b/SimDynamics/DynamicsEngine/DynamicsRobot.h @@ -96,7 +96,7 @@ protected: { float jointValueTarget; VirtualRobot::RobotNodePtr node; - DynamicsObjectPtr dynNode; + //DynamicsObjectPtr dynNode; // if node is a joint without model, there is no dyn node! bool enabled; }; diff --git a/SimDynamics/examples/BulletDebugViewerGlut/BulletDebugViewerGlut.cpp b/SimDynamics/examples/BulletDebugViewerGlut/BulletDebugViewerGlut.cpp index 296b87bde75259a32ea8c5ca7e3dda1cc9ab5989..d433d67cde06588b6fa593a22d43fae3eaddb34e 100644 --- a/SimDynamics/examples/BulletDebugViewerGlut/BulletDebugViewerGlut.cpp +++ b/SimDynamics/examples/BulletDebugViewerGlut/BulletDebugViewerGlut.cpp @@ -13,6 +13,31 @@ using namespace SimDynamics; int main(int argc,char* argv[]) { + VirtualRobot::RuntimeEnvironment::considerKey("robot"); + VirtualRobot::RuntimeEnvironment::processCommandLine(argc,argv); + VirtualRobot::RuntimeEnvironment::print(); + + cout << " --- START --- " << endl; + + + //std::string robFile("robots/examples/SimpleRobot/Joint5.xml"); + //std::string robFile("robots/iCub/iCub.xml"); + std::string robFile("robots/ArmarIII/ArmarIII.xml"); + //std::string robFile("robots/iCub/iCub_RightHand.xml"); + //std::string robFile("robots/iCub/iCub_testFinger.xml"); + + if (VirtualRobot::RuntimeEnvironment::hasValue("robot")) + { + std::string robFile2 = VirtualRobot::RuntimeEnvironment::getValue("robot"); + if (VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(robFile2)) + { + robFile = robFile2; + } + } + cout << "Using robot at " << robFile << endl; + + + SimDynamics::DynamicsWorldPtr world = SimDynamics::DynamicsWorld::Init(); SIMDYNAMICS_ASSERT(world); @@ -25,18 +50,14 @@ int main(int argc,char* argv[]) dynObj->setPosition(Eigen::Vector3f(3000,3000,1000.0f)); world->addObject(dynObj); - //std::string robFile("robots/examples/SimpleRobot/Joint5.xml"); - //std::string robFile("robots/iCub/iCub.xml"); - std::string robFile("robots/ArmarIII/ArmarIII.xml"); - //std::string robFile("robots/iCub/iCub_RightHand.xml"); - //std::string robFile("robots/iCub/iCub_testFinger.xml"); + VirtualRobot::RuntimeEnvironment::getDataFileAbsolute(robFile); VirtualRobot::RobotPtr robot = VirtualRobot::RobotIO::loadRobot(robFile); if (robot) { Eigen::Matrix4f gp = Eigen::Matrix4f::Identity(); //gp(2,3) = 35.0f; - gp(2,3) = 400.0f; + gp(2,3) = 800.0f; robot->setGlobalPose(gp); DynamicsRobotPtr dynRob = world->CreateDynamicsRobot(robot); dynRob->disableActuation(); diff --git a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp index b6eacbb97a904a7ff76b3e7a602aa1091bb31e1a..5348a5b526a3d3aa7b852a92f599e92820d3ea4b 100644 --- a/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp +++ b/SimDynamics/examples/SimDynamicsViewer/simDynamicsWindow.cpp @@ -278,9 +278,10 @@ bool SimDynamicsWindow::loadRobot(std::string robotFilename) } try { + //VirtualRobot::BoundingBox bbox = robot->getBoundingBox(); //robot->print(); Eigen::Matrix4f gp = Eigen::Matrix4f::Identity(); - gp(2,3) = 200.0f; + gp(2,3) = 800.0f; robot->setGlobalPose(gp); dynamicsRobot = dynamicsWorld->CreateDynamicsRobot(robot); dynamicsWorld->addRobot(dynamicsRobot); diff --git a/VirtualRobot/BoundingBox.cpp b/VirtualRobot/BoundingBox.cpp index 8a5f105ffa8a7dcdb95db004249e07cb60383292..dfe98692fd9ebc722adaa11f86d107360e4315c8 100644 --- a/VirtualRobot/BoundingBox.cpp +++ b/VirtualRobot/BoundingBox.cpp @@ -85,5 +85,22 @@ void BoundingBox::addPoint( const Eigen::Vector3f &p ) } } +Eigen::Vector3f BoundingBox::getMax() const +{ + return max; +} + +Eigen::Vector3f BoundingBox::getMin() const +{ + return min; +} + + +void BoundingBox::clear() +{ + min.setZero(); + max.setZero(); +} + } diff --git a/VirtualRobot/BoundingBox.h b/VirtualRobot/BoundingBox.h index d42883a1a0a266f221457022d379f4edeb710d43..45131d7c66d5f6a6c049f628ea62c720bddd4104 100644 --- a/VirtualRobot/BoundingBox.h +++ b/VirtualRobot/BoundingBox.h @@ -25,29 +25,58 @@ #include "VirtualRobotImportExport.h" #include "MathTools.h" +#include "CollisionDetection/CollisionChecker.h" #include <Eigen/Core> #include <vector> namespace VirtualRobot { +/*! + An axis oriented bounding box +*/ class VIRTUAL_ROBOT_IMPORT_EXPORT BoundingBox { + friend class ClollisionChecker; public: EIGEN_MAKE_ALIGNED_OPERATOR_NEW BoundingBox(); BoundingBox(const std::vector< Eigen::Vector3f > &p); + /*! + Returns true, if plane "hits" this bounding box. + */ bool planeGoesThrough(const VirtualRobot::MathTools::Plane &p); + /*! + Returns 8 points that define the bounding box + */ std::vector <Eigen::Vector3f> getPoints(); + //! Print some info void print(); + /*! + Consider these points for min/max calculation + */ void addPoints( const std::vector < Eigen::Vector3f > &p ); + + /*! + Consider this point for min/max calculation + */ void addPoint (const Eigen::Vector3f &p); + //! The axis oriented minimum value + Eigen::Vector3f getMin() const; + + //! The axis oriented maximum value + Eigen::Vector3f getMax() const; + + //! set min/max to zero. + void clear(); + +protected: Eigen::Vector3f min; Eigen::Vector3f max; }; diff --git a/VirtualRobot/EndEffector/EndEffector.cpp b/VirtualRobot/EndEffector/EndEffector.cpp index dcbcfcf1eeed52023fa5b19e10e5239db289f252..48f5163078dd8680e653f5d6a8c9f712d6a5f83c 100644 --- a/VirtualRobot/EndEffector/EndEffector.cpp +++ b/VirtualRobot/EndEffector/EndEffector.cpp @@ -419,11 +419,11 @@ float EndEffector::getApproximatedLength() if (statics[j]->getCollisionModel()) { BoundingBox bb = statics[j]->getCollisionModel()->getBoundingBox(); - bb_all.addPoint(bb.min); - bb_all.addPoint(bb.max); + bb_all.addPoint(bb.getMin()); + bb_all.addPoint(bb.getMax()); } } - Eigen::Vector3f d = bb_all.max - bb_all.min; + Eigen::Vector3f d = bb_all.getMax() - bb_all.getMin(); float maxStatic = d.norm(); return maxStatic + maxActor; diff --git a/VirtualRobot/EndEffector/EndEffectorActor.cpp b/VirtualRobot/EndEffector/EndEffectorActor.cpp index 627e5a553760b52f0d4f4b06622154f17258fbca..38abc5cb83ab2cbf56b1022562e2bdd6089f2067 100644 --- a/VirtualRobot/EndEffector/EndEffectorActor.cpp +++ b/VirtualRobot/EndEffector/EndEffectorActor.cpp @@ -406,11 +406,11 @@ float EndEffectorActor::getApproximatedLength() if (actors[j].robotNode->getCollisionModel()) { BoundingBox bb = actors[j].robotNode->getCollisionModel()->getBoundingBox(); - bb_all.addPoint(bb.min); - bb_all.addPoint(bb.max); + bb_all.addPoint(bb.getMin()); + bb_all.addPoint(bb.getMax()); } } - Eigen::Vector3f d = bb_all.max - bb_all.min; + Eigen::Vector3f d = bb_all.getMax() - bb_all.getMin(); return d.norm(); } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp index 0f3cb4a2cb3502a78e36204a363877c740d3c350..b6952c16381e40d4578267a3ca3859c2f9f4a073 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp @@ -1013,12 +1013,14 @@ namespace VirtualRobot { res->addChild(ds); SoTranslation *tr = new SoTranslation(); - float x1 = std::min(bbox.min(0), bbox.max(0)); - float x2 = std::max(bbox.min(0), bbox.max(0)); - float y1 = std::min(bbox.min(1), bbox.max(1)); - float y2 = std::max(bbox.min(1), bbox.max(1)); - float z1 = std::min(bbox.min(2), bbox.max(2)); - float z2 = std::max(bbox.min(2), bbox.max(2)); + Eigen::Vector3f mi = bbox.getMin(); + Eigen::Vector3f ma = bbox.getMax(); + float x1 = std::min(mi(0), ma(0)); + float x2 = std::max(mi(0), ma(0)); + float y1 = std::min(mi(1), ma(1)); + float y2 = std::max(mi(1), ma(1)); + float z1 = std::min(mi(2), ma(2)); + float z2 = std::max(mi(2), ma(2)); float x = x1 + (x2 - x1) *0.5f; float y = y1 + (y2 - y1) *0.5f; float z = z1 + (z2 - z1) *0.5f; diff --git a/VirtualRobot/Visualization/TriMeshModel.cpp b/VirtualRobot/Visualization/TriMeshModel.cpp index fce60b82b781ad593bd8f16c3197713b2cd68b5d..ec3498c56ae58e413d856e73ec9ec51c1206c68e 100644 --- a/VirtualRobot/Visualization/TriMeshModel.cpp +++ b/VirtualRobot/Visualization/TriMeshModel.cpp @@ -97,11 +97,7 @@ void TriMeshModel::addFace(const MathTools::TriangleFace& face) void TriMeshModel::addVertex(const Eigen::Vector3f& vertex) { vertices.push_back(vertex); - for (int i=0;i<3;i++) - { - if (vertex(i) < boundingBox.min(i)) boundingBox.min(i) = vertex(i); - if (vertex(i) > boundingBox.max(i)) boundingBox.max(i) = vertex(i); - } + boundingBox.addPoint(vertex); } @@ -113,8 +109,7 @@ void TriMeshModel::clear() { vertices.clear(); faces.clear(); - boundingBox.min.setZero(); - boundingBox.max.setZero(); + boundingBox.clear(); } diff --git a/VirtualRobot/examples/SceneViewer/SceneViewer.ui b/VirtualRobot/examples/SceneViewer/SceneViewer.ui index 95e1afdfb9231a4b0f4527fd24d3ad60f5c9bf2c..c5a15fc21a83f5875cc596a0e9ed01a2beaff165 100644 --- a/VirtualRobot/examples/SceneViewer/SceneViewer.ui +++ b/VirtualRobot/examples/SceneViewer/SceneViewer.ui @@ -6,8 +6,8 @@ <rect> <x>0</x> <y>0</y> - <width>790</width> - <height>659</height> + <width>792</width> + <height>657</height> </rect> </property> <property name="windowTitle"> @@ -199,10 +199,10 @@ <widget class="QGroupBox" name="groupBox_3"> <property name="geometry"> <rect> - <x>0</x> + <x>10</x> <y>470</y> <width>181</width> - <height>61</height> + <height>101</height> </rect> </property> <property name="title"> @@ -218,6 +218,29 @@ </rect> </property> </widget> + <widget class="QComboBox" name="comboBoxGrasp"> + <property name="geometry"> + <rect> + <x>40</x> + <y>70</y> + <width>131</width> + <height>22</height> + </rect> + </property> + </widget> + <widget class="QLabel" name="label_5"> + <property name="geometry"> + <rect> + <x>30</x> + <y>50</y> + <width>91</width> + <height>20</height> + </rect> + </property> + <property name="text"> + <string>Grasp</string> + </property> + </widget> </widget> </widget> </item> @@ -228,7 +251,7 @@ <rect> <x>0</x> <y>0</y> - <width>790</width> + <width>792</width> <height>21</height> </rect> </property> diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp index 9ea27e5bd7e908851ef673030acedd99fedaff14..4e91901fabef5e24cd41fb9203d1f20ab755b94c 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.cpp @@ -4,6 +4,8 @@ #include "VirtualRobot/Workspace/Reachability.h" #include "VirtualRobot/ManipulationObject.h" #include "VirtualRobot/XML/ObjectIO.h" +#include "VirtualRobot/Grasping/GraspSet.h" +#include "VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h" #include <QFileDialog> #include <Eigen/Geometry> @@ -78,6 +80,7 @@ void showSceneWindow::setupUI() connect(UI.pushButtonEEFClose, SIGNAL(clicked()), this, SLOT(closeHand())); connect(UI.pushButtonEEFOpen, SIGNAL(clicked()), this, SLOT(openHand())); connect(UI.comboBoxEEF, SIGNAL(activated(int)), this, SLOT(selectEEF(int))); + connect(UI.comboBoxGrasp, SIGNAL(activated(int)), this, SLOT(selectGrasp(int))); /* connect(UI.checkBoxColModel, SIGNAL(clicked()), this, SLOT(collisionModel())); @@ -139,6 +142,27 @@ void showSceneWindow::buildVisu() if (visualisationNode) sceneVisuSep->addChild(visualisationNode); + updateGraspVisu(); + + +} + +void showSceneWindow::updateGraspVisu() +{ + // build grasp visu + graspVisu->removeAllChildren(); + if (UI.comboBoxGrasp->currentIndex()>0 && currentObject && currentEEF && currentGrasp) + { + //SoSeparator* visu = CoinVisualizationFactory::CreateGraspVisualization(currentGrasp, currentEEF,currentObject->getGlobalPose()); + SoMatrixTransform* mt = CoinVisualizationFactory::getMatrixTransformScaleMM2M(currentGrasp->getTcpPoseGlobal(currentObject->getGlobalPose())); + graspVisu->addChild(mt); + + std::string t = currentGrasp->getName(); + SoSeparator* visu = CoinVisualizationFactory::CreateCoordSystemVisualization(1.0f,&t); + + if (visu) + graspVisu->addChild(visu); + } } int showSceneWindow::main() @@ -328,12 +352,35 @@ void showSceneWindow::selectEEF(int nr) } std::string eefStr(UI.comboBoxEEF->currentText().toAscii()); currentEEF = currentRobot->getEndEffector(eefStr); + updateGrasps(); } void showSceneWindow::selectObject(int nr) { - if (nr<0 || nr>=UI.comboBoxObject->count()) + if (!scene || nr<0 || nr>=UI.comboBoxObject->count()) + return; + std::string ob = UI.comboBoxObject->currentText().toAscii(); + currentObject.reset(); + if (scene->hasManipulationObject(ob)) + { + VirtualRobot::ManipulationObjectPtr mo = scene->getManipulationObject(ob); + currentObject = boost::dynamic_pointer_cast<SceneObject>(mo); + } + updateGrasps(); +} + +void showSceneWindow::selectGrasp(int nr) +{ + currentGrasp.reset(); + if (nr<=0 || nr>=UI.comboBoxGrasp->count() || !currentGraspSet) + { return; + } + std::string grStr(UI.comboBoxGrasp->currentText().toAscii()); + if (currentGraspSet->hasGrasp(grStr)) + currentGrasp = currentGraspSet->getGrasp(grStr); + + updateGraspVisu(); } void showSceneWindow::updateGui() @@ -377,6 +424,28 @@ void showSceneWindow::updateGui() } } +void showSceneWindow::updateGrasps() +{ + currentGraspSet.reset(); + UI.comboBoxGrasp->clear(); + QString t("-"); + UI.comboBoxGrasp->addItem(t); + VirtualRobot::ManipulationObjectPtr mo = boost::dynamic_pointer_cast<ManipulationObject>(currentObject); + + if (mo && currentEEF) + { + currentGraspSet = mo->getGraspSet(currentEEF); + if (currentGraspSet) + for (unsigned int i=0;i<currentGraspSet->getSize();i++) + { + t = currentGraspSet->getGrasp(i)->getName().c_str(); + UI.comboBoxGrasp->addItem(t); + } + } + UI.comboBoxGrasp->setCurrentIndex(0); + selectGrasp(0); +} + void showSceneWindow::closeHand() { if (!currentEEF) diff --git a/VirtualRobot/examples/SceneViewer/showSceneWindow.h b/VirtualRobot/examples/SceneViewer/showSceneWindow.h index 311cdd5589038e54d1e7151dd87ede4fc1e76342..8c000621e4513827ddcdec10c0829ee140620f41 100644 --- a/VirtualRobot/examples/SceneViewer/showSceneWindow.h +++ b/VirtualRobot/examples/SceneViewer/showSceneWindow.h @@ -49,6 +49,7 @@ public slots: void selectRobot(int nr); void selectObject(int nr); + void selectGrasp(int nr); void selectEEF(int nr); void selectRobotConfig(int nr); void selectTrajectory(int nr); @@ -62,6 +63,8 @@ public slots: protected: void updateGui(); + void updateGrasps(); + void updateGraspVisu(); void setupUI(); QString formatString(const char *s, float f); void buildVisu(); @@ -72,6 +75,9 @@ protected: SoSeparator *sceneSep; SoSeparator *sceneVisuSep; SoSeparator *graspVisu; + VirtualRobot::GraspPtr currentGrasp; + VirtualRobot::GraspSetPtr currentGraspSet; + VirtualRobot::SceneObjectPtr currentObject; VirtualRobot::RobotPtr currentRobot; VirtualRobot::TrajectoryPtr currentTrajectory; VirtualRobot::EndEffectorPtr currentEEF;