diff --git a/GeometricPlanning/visualization.cpp b/GeometricPlanning/visualization.cpp index 7dc943d41c6bb581b8936ec7eb34557b3742ee8a..c6ed9054b619add1c90718d6381f6f4013ba443a 100644 --- a/GeometricPlanning/visualization.cpp +++ b/GeometricPlanning/visualization.cpp @@ -25,27 +25,20 @@ namespace simox::geometric_planning constexpr std::size_t numberOfCircleParts = 20; inline const simox::Color DefaultColor = simox::Color::blue(); - constexpr float - scaleColor(const auto colorVal) - { - return colorVal / 255.f; - } - + namespace detail { SoNode* visualizePathLine(const geometric_planning::ParametricPath& path) { - const auto startPos = path.getPose(path.parameterRange().min); - const auto endPos = path.getPose(path.parameterRange().max); + const auto startPos = path.getPosition(path.parameterRange().min); + const auto endPos = path.getPosition(path.parameterRange().max); return VirtualRobot::CoinVisualizationFactory::createCoinLine( - startPos.matrix(), - endPos.matrix(), + startPos, + endPos, defaultWidth, - scaleColor(DefaultColor.r), - scaleColor(DefaultColor.g), - scaleColor(DefaultColor.b)); + DefaultColor); } @@ -65,9 +58,7 @@ namespace simox::geometric_planning circleSegment->getRadius(), circleCompletion, defaultWidth, - scaleColor(DefaultColor.r), - scaleColor(DefaultColor.g), - scaleColor(DefaultColor.b), + DefaultColor, numberOfCircleParts); diff --git a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp index 7fc3a40a556f8cbaf385377a00fe6bcb91c7a99c..d03f473961fff33e8a958bc0c7521083479aaa5a 100644 --- a/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp +++ b/MotionPlanning/examples/PlatformDemo/PlatformWindow.cpp @@ -321,19 +321,12 @@ void PlatformWindow::selectColModelEnv(const std::string &name) this->colModelEnv = scene->getSceneObjectSet(name); } -void PlatformWindow::updateDistVisu(const Eigen::Vector3f &a, const Eigen::Vector3f &b) +void PlatformWindow::updateDistVisu(const Eigen::Vector3f &from, const Eigen::Vector3f &to) { distSep->removeAllChildren(); if (UI.checkBoxShowDistance->isChecked()) { - Eigen::Matrix4f from; - Eigen::Matrix4f to; - from.setIdentity(); - to.setIdentity(); - from.block(0,3,3,1) = a; - to.block(0,3,3,1) = b; - - SoNode * c = CoinVisualizationFactory::createCoinLine(from, to, 5.0f, 1.0f, 0.2f, 0.2f); + SoNode * c = CoinVisualizationFactory::createCoinLine(from, to, 5.0f, VirtualRobot::CoinVisualizationFactory::Color(1.0f, 0.2f, 0.2f)); distSep->addChild(c); } } @@ -612,6 +605,3 @@ void PlatformWindow::redraw() this->update(); viewer->scheduleRedraw(); } - - - diff --git a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp index 03c1cb01c3de4bd835f6868eea84777a042a1a24..524f04e86b73adecf1706b073e9a9efcdda7abb9 100644 --- a/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp +++ b/VirtualRobot/Import/URDF/SimoxURDFFactory.cpp @@ -22,6 +22,7 @@ #include <VirtualRobot/Nodes/RobotNodeRevoluteFactory.h> #include <VirtualRobot/RuntimeEnvironment.h> +#include <SimoxUtility/color.h> using namespace std; @@ -301,7 +302,7 @@ namespace VirtualRobot } - VirtualRobot::VisualizationNodePtr SimoxURDFFactory::convertVisu(std::shared_ptr<urdf::Geometry> g, urdf::Pose& pose, const std::string& basePath) + VirtualRobot::VisualizationNodePtr SimoxURDFFactory::convertVisu(const std::shared_ptr<urdf::Geometry>& g, const urdf::Pose& pose, const std::string& basePath) { const float scale = 1000.0f; // mm @@ -313,19 +314,25 @@ namespace VirtualRobot return res; } + const auto kit_green = ::simox::Color::kit_green(128); + constexpr float alpha = 0.5; + const VisualizationFactory::Color color(kit_green.r / 255., kit_green.g / 255., kit_green.b / 255, alpha); + + + switch (g->type) { case urdf::Geometry::BOX: { std::shared_ptr<urdf::Box> b = std::dynamic_pointer_cast<urdf::Box>(g); - res = factory->createBox(b->dim.x * scale, b->dim.y * scale, b->dim.z * scale); + res = factory->createBox(b->dim.x * scale, b->dim.y * scale, b->dim.z * scale, color); } break; case urdf::Geometry::SPHERE: { std::shared_ptr<urdf::Sphere> s = std::dynamic_pointer_cast<urdf::Sphere>(g); - res = factory->createSphere(s->radius * scale); + res = factory->createSphere(s->radius * scale, color); } break; @@ -333,7 +340,7 @@ namespace VirtualRobot case urdf::Geometry::CYLINDER: { std::shared_ptr<urdf::Cylinder> c = std::dynamic_pointer_cast<urdf::Cylinder>(g); - res = factory->createCylinder(c->radius * scale, c->length * scale); + res = factory->createCylinder(c->radius * scale, c->length * scale, color); } break; @@ -342,7 +349,7 @@ namespace VirtualRobot { std::shared_ptr<urdf::Mesh> m = std::dynamic_pointer_cast<urdf::Mesh>(g); std::string filename = getFilename(m->filename, basePath); - res = factory->getVisualizationFromFile(filename, false, m->scale.x, m->scale.y, m->scale.z); + res = factory->getVisualizationFromFile(filename, false, m->scale.x * scale, m->scale.y * scale, m->scale.z * scale); } break; @@ -358,7 +365,8 @@ namespace VirtualRobot // inventor and urdf differ in the conventions for cylinders p = p * MathTools::axisangle2eigen4f(Eigen::Vector3f::UnitX(), M_PI_2); } - factory->applyDisplacement(res, p); + // factory->applyDisplacement(res, p); + res->setLocalPose(p); } return res; diff --git a/VirtualRobot/Import/URDF/SimoxURDFFactory.h b/VirtualRobot/Import/URDF/SimoxURDFFactory.h index 37b44cc7e042ff4372e61ae758585ee1e0a16b9c..308a35d6b2aebbc98a3ccd39af871c51f313269b 100644 --- a/VirtualRobot/Import/URDF/SimoxURDFFactory.h +++ b/VirtualRobot/Import/URDF/SimoxURDFFactory.h @@ -79,7 +79,7 @@ namespace VirtualRobot RobotNodePtr createBodyNode(const std::string& name, RobotPtr robot, std::shared_ptr<urdf::Link> urdfBody, const std::string& basePath, bool useColModelsIfNoVisuModel = true); RobotNodePtr createJointNode(RobotPtr robot, std::shared_ptr<urdf::Joint> urdfJoint); Eigen::Matrix4f convertPose(const urdf::Pose& p) const; - VirtualRobot::VisualizationNodePtr convertVisu(std::shared_ptr<urdf::Geometry> g, urdf::Pose& pose, const std::string& basePath); + VirtualRobot::VisualizationNodePtr convertVisu(const std::shared_ptr<urdf::Geometry>& g, const urdf::Pose& pose, const std::string& basePath); VirtualRobot::VisualizationNodePtr convertVisuArray(std::vector<std::shared_ptr<urdf::Visual> > visu_array, const std::string& basePath); VirtualRobot::VisualizationNodePtr convertVisuArray(std::vector<std::shared_ptr<urdf::Collision> > visu_array, const std::string& basePath); std::string getFilename(const std::string& f, const std::string& basePath); diff --git a/VirtualRobot/Nodes/RobotNode.cpp b/VirtualRobot/Nodes/RobotNode.cpp index e660813af4584d71cabf34c9a7e63e76f6c00840..8298691bfc22221a3daf83ba7a676d53841392a0 100644 --- a/VirtualRobot/Nodes/RobotNode.cpp +++ b/VirtualRobot/Nodes/RobotNode.cpp @@ -12,6 +12,7 @@ #include <VirtualRobot/XML/BaseIO.h> #include <Eigen/Core> +#include <Eigen/src/Geometry/Transform.h> #include <filesystem> #include <algorithm> @@ -821,17 +822,18 @@ namespace VirtualRobot } // create visu - Eigen::Matrix4f i = Eigen::Matrix4f::Identity(); - if (!localTransformation.isIdentity()) { VisualizationNodePtr visualizationNode1; + if (parRN && parRN->getVisualization()) { // add to parent node (pre joint trafo moves with parent!) //visualizationNode1 = visualizationFactory->createLine(parRN->postJointTransformation, parRN->postJointTransformation*localTransformation); - visualizationNode1 = visualizationFactory->createLine(Eigen::Matrix4f::Identity(), localTransformation); + const Eigen::Vector3f localTrafoPos = Eigen::Isometry3f{localTransformation}.translation(); + + visualizationNode1 = visualizationFactory->createLine(Eigen::Vector3f::Zero(), localTrafoPos); if (visualizationNode1) { @@ -840,7 +842,9 @@ namespace VirtualRobot } else { - visualizationNode1 = visualizationFactory->createLine(localTransformation.inverse(), i); + const Eigen::Vector3f localTrafoInvPos = Eigen::Isometry3f{localTransformation}.inverse().translation(); + + visualizationNode1 = visualizationFactory->createLine(localTrafoInvPos, Eigen::Vector3f::Zero()); if (visualizationNode1) { diff --git a/VirtualRobot/Obstacle.cpp b/VirtualRobot/Obstacle.cpp index 2f1121b9a902b2d65b300f6dfabc366c8c6538d7..f0811cc3707055e0650fe4ca65ce76c20b5bb59f 100644 --- a/VirtualRobot/Obstacle.cpp +++ b/VirtualRobot/Obstacle.cpp @@ -86,7 +86,7 @@ namespace VirtualRobot VisualizationNodePtr visu = visualizationFactory->getVisualizationFromPrimitives(primitives,false,color); */ - VisualizationNodePtr visu = visualizationFactory->createBox(width, height, depth, color.r, color.g, color.b); + VisualizationNodePtr visu = visualizationFactory->createBox(width, height, depth, color); if (!visu) { @@ -132,7 +132,7 @@ namespace VirtualRobot return result; } - VisualizationNodePtr visu = visualizationFactory->createSphere(radius, color.r, color.g, color.b); + VisualizationNodePtr visu = visualizationFactory->createSphere(radius, color); /*std::vector<Primitive::PrimitivePtr> primitives; Primitive::PrimitivePtr p(new Primitive::Sphere(radius)); @@ -184,7 +184,7 @@ namespace VirtualRobot return result; } - VisualizationNodePtr visu = visualizationFactory->createCylinder(radius, height, color.r, color.g, color.b); + VisualizationNodePtr visu = visualizationFactory->createCylinder(radius, height, color); /*std::vector<Primitive::PrimitivePtr> primitives; Primitive::PrimitivePtr p(new Primitive::Cylinder(radius, height)); @@ -343,5 +343,3 @@ namespace VirtualRobot } } // namespace - - diff --git a/VirtualRobot/SceneObject.cpp b/VirtualRobot/SceneObject.cpp index 3e62d88805693bc740d5ffb565c1d0b8c94c914b..734ec473976bfd677d1607a1853d0a6e8c878e24 100644 --- a/VirtualRobot/SceneObject.cpp +++ b/VirtualRobot/SceneObject.cpp @@ -320,8 +320,8 @@ namespace VirtualRobot // create visu if (!comModel) { - VisualizationNodePtr comModel1 = visualizationFactory->createSphere(7.05f, 1.0f, 0.2f, 0.2f); - VisualizationNodePtr comModel2 = visualizationFactory->createBox(10.0f, 10.0f, 10.0f, 0.2f, 0.2f, 1.0f); + VisualizationNodePtr comModel1 = visualizationFactory->createSphere(7.05f, VisualizationFactory::Color(1.0f, 0.2f, 0.2f)); + VisualizationNodePtr comModel2 = visualizationFactory->createBox(10.0f, 10.0f, 10.0f, VisualizationFactory::Color(0.2f, 0.2f, 1.0f)); std::vector<VisualizationNodePtr> v; v.push_back(comModel1); v.push_back(comModel2); @@ -1535,8 +1535,10 @@ namespace VirtualRobot } else { + const auto color = simox::color::Color::kit_blue(128); + VisualizationFactoryPtr visualizationFactory = VisualizationFactory::first(NULL); - setCollisionModel(std::make_shared<CollisionModel>(visualizationFactory->getVisualizationFromPrimitives(primitives), + setCollisionModel(std::make_shared<CollisionModel>(visualizationFactory->getVisualizationFromPrimitives(primitives, false, color), getName() + "_PrimitiveModel", CollisionCheckerPtr())); } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp index 7981e51f177f2d0b3ec9a9cf5ad3f4136497ee02..7a4e74191658a561faadbe05d921508a8340f759 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.cpp @@ -142,7 +142,7 @@ namespace VirtualRobot * \param boundingBox Use bounding box instead of full model. * \return instance of VirtualRobot::CoinVisualizationNode upon success and VirtualRobot::VisualizationNode on error. */ - VisualizationNodePtr CoinVisualizationFactory::getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& primitives, bool boundingBox, Color color) + VisualizationNodePtr CoinVisualizationFactory::getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& primitives, bool boundingBox,const Color& color) { VisualizationNodePtr visualizationNode = VisualizationNodePtr(new VisualizationNode()); SoSeparator* coinVisualization = new SoSeparator(); @@ -174,7 +174,7 @@ namespace VirtualRobot return visualizationNode; } - SoNode* CoinVisualizationFactory::GetNodeFromPrimitive(Primitive::PrimitivePtr primitive, bool boundingBox, Color color) + SoNode* CoinVisualizationFactory::GetNodeFromPrimitive(Primitive::PrimitivePtr primitive, bool boundingBox,const Color& color) { SoSeparator* coinVisualization = new SoSeparator; SoNode* c = getColorNode(color); @@ -509,7 +509,7 @@ namespace VirtualRobot return coinFactory; } - VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createBox(float width, float height, float depth, float colorR, float colorG, float colorB) + VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createBox(float width, float height, float depth, const Color& color) { SoSeparator* s = new SoSeparator(); s->ref(); @@ -520,8 +520,9 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); + m->transparency.setValue(color.transparency); SoCube* c = new SoCube(); s->addChild(c); @@ -534,7 +535,7 @@ namespace VirtualRobot return visualizationNode; } - SoNode* CoinVisualizationFactory::createCoinLine(const Eigen::Matrix4f& from, const Eigen::Matrix4f& to, float width, float colorR, float colorG, float colorB) + SoNode* CoinVisualizationFactory::createCoinLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width, const Color& color) { SoSeparator* s = new SoSeparator(); s->ref(); @@ -544,20 +545,13 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); // create line - float x = from(0, 3); - float y = from(1, 3); - float z = from(2, 3); - float x2 = to(0, 3); - float y2 = to(1, 3); - float z2 = to(2, 3); - SbVec3f points[2]; - points[0].setValue(x2, y2, z2); - points[1].setValue(x, y, z); + points[0].setValue(to.x(), to.y(), to.z()); + points[1].setValue(from.x(), from.y(), from.z()); SoDrawStyle* lineSolutionStyle = new SoDrawStyle(); lineSolutionStyle->lineWidth.setValue(width); @@ -576,7 +570,7 @@ namespace VirtualRobot return s; } - SoNode* CoinVisualizationFactory::createCoinPartCircle(float radius, float circleCompletion, float width, float colorR, float colorG, float colorB, size_t numberOfCircleParts, float offset) + SoNode* CoinVisualizationFactory::createCoinPartCircle(float radius, float circleCompletion, float width, const Color& color, size_t numberOfCircleParts, float offset) { SoSeparator* s = new SoSeparator(); s->ref(); @@ -586,8 +580,8 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); SoCoordinate3* coordinate3 = new SoCoordinate3; circleCompletion = std::min<float>(1.0f, circleCompletion); circleCompletion = std::max<float>(-1.0f, circleCompletion); @@ -627,34 +621,24 @@ namespace VirtualRobot return s; } - VisualizationNodePtr CoinVisualizationFactory::createLine(const Eigen::Matrix4f& from, const Eigen::Matrix4f& to, float width, float colorR, float colorG, float colorB) + VisualizationNodePtr CoinVisualizationFactory::createLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width, const Color& color) { - SoNode* s = createCoinLine(from, to, width, colorR, colorG, colorB); + SoNode* s = createCoinLine(from, to, width, color); VisualizationNodePtr visualizationNode(new CoinVisualizationNode(s)); return visualizationNode; } - VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width /*= 1.0f*/, float colorR /*= 0.5f*/, float colorG /*= 0.5f*/, float colorB /*= 0.5f*/) - { - Eigen::Matrix4f fromM; - fromM.setIdentity(); - fromM.block(0, 3, 3, 1) = from; - Eigen::Matrix4f toM; - toM.setIdentity(); - toM.block(0, 3, 3, 1) = to; - return createLine(from, to, width, colorR, colorG, colorB); - } - VisualizationNodePtr CoinVisualizationFactory::createSphere(float radius, float colorR, float colorG, float colorB) + VisualizationNodePtr CoinVisualizationFactory::createSphere(float radius, const Color& color) { return VisualizationNodePtr( new CoinVisualizationNode( CreateSphere(Eigen::Vector3f::Zero(), radius, - colorR, colorG, colorB))); + color))); } - VisualizationNodePtr CoinVisualizationFactory::createCylinder(float radius, float height, float colorR, float colorG, float colorB) + VisualizationNodePtr CoinVisualizationFactory::createCylinder(float radius, float height, const Color& color) { SoSeparator* s = new SoSeparator(); s->ref(); @@ -664,8 +648,9 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); + m->transparency.setValue(color.transparency); SoCylinder* c = new SoCylinder(); s->addChild(c); @@ -677,9 +662,9 @@ namespace VirtualRobot return visualizationNode; } - VisualizationNodePtr CoinVisualizationFactory::createCircle(float radius, float circleCompletion, float width, float colorR, float colorG, float colorB, size_t numberOfCircleParts) + VisualizationNodePtr CoinVisualizationFactory::createCircle(float radius, float circleCompletion, float width, const Color& color, size_t numberOfCircleParts) { - SoNode* s = createCoinPartCircle(radius, circleCompletion, width, colorR, colorB, colorG, numberOfCircleParts); + SoNode* s = createCoinPartCircle(radius, circleCompletion, width, color, numberOfCircleParts); VisualizationNodePtr visualizationNode(new CoinVisualizationNode(s)); s->unref(); return visualizationNode; @@ -837,7 +822,7 @@ namespace VirtualRobot return result; } - VisualizationNodePtr CoinVisualizationFactory::createText(const std::string& text, bool billboard, float scaling, Color c, float offsetX, float offsetY, float offsetZ) + VisualizationNodePtr CoinVisualizationFactory::createText(const std::string& text, bool billboard, float scaling, const Color& c, float offsetX, float offsetY, float offsetZ) { SoSeparator* res = new SoSeparator(); res->ref(); @@ -866,7 +851,7 @@ namespace VirtualRobot return visualizationNode; } - VisualizationNodePtr CoinVisualizationFactory::createTorus(float radius, float tubeRadius, float completion, float colorR, float colorG, float colorB, float transparency, int sides, int rings) + VisualizationNodePtr CoinVisualizationFactory::createTorus(float radius, float tubeRadius, float completion, const Color& color, int sides, int rings) { SoSeparator* sep = new SoSeparator(); sep->ref(); @@ -874,7 +859,7 @@ namespace VirtualRobot { TriMeshModelPtr triMesh = TriMeshModelPtr(new TriMeshModel()); - triMesh->addColor(VirtualRobot::VisualizationFactory::Color(colorR, colorG, colorB, transparency)); + triMesh->addColor(color); int numVerticesPerRow = sides + 1; int numVerticesPerColumn = rings + 1; @@ -1020,7 +1005,7 @@ namespace VirtualRobot return textSep; } - SoSeparator* CoinVisualizationFactory::CreateVertexVisualization(const Eigen::Vector3f& position, float radius, float transparency, float colorR /*= 0.5f*/, float colorG /*= 0.5f*/, float colorB /*= 0.5f*/) + SoSeparator* CoinVisualizationFactory::CreateVertexVisualization(const Eigen::Vector3f& position, float radius, const Color& color) { SoSeparator* res = new SoSeparator; res->ref(); @@ -1039,11 +1024,11 @@ namespace VirtualRobot // Set material SoMaterial* m = new SoMaterial; - m->transparency.setValue(transparency); + m->transparency.setValue(color.transparency); - m->diffuseColor.setValue(colorR, colorG, colorB); - m->ambientColor.setValue(colorR, colorG, colorB); + m->diffuseColor.setValue(color.r, color.g, color.b); + m->ambientColor.setValue(color.r, color.g, color.b); // Set shape SoSphere* s = new SoSphere; @@ -1057,7 +1042,7 @@ namespace VirtualRobot } - SoSeparator* CoinVisualizationFactory::CreateVerticesVisualization(const std::vector<Eigen::Vector3f>& positions, float radius, VisualizationFactory::Color color) + SoSeparator* CoinVisualizationFactory::CreateVerticesVisualization(const std::vector<Eigen::Vector3f>& positions, float radius,const Color& color) { SoSeparator* pclSep = new SoSeparator; @@ -1174,21 +1159,21 @@ namespace VirtualRobot } } - VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createVertexVisualization(const Eigen::Vector3f& position, float radius, float transparency, float colorR /*= 0.5f*/, float colorG /*= 0.5f*/, float colorB /*= 0.5f*/) + VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createVertexVisualization(const Eigen::Vector3f& position, float radius, const Color& color) { - VisualizationNodePtr node(new CoinVisualizationNode(CreateVertexVisualization(position, radius, transparency, colorR, colorG, colorB))); + VisualizationNodePtr node(new CoinVisualizationNode(CreateVertexVisualization(position, radius, color))); return node; } - VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createPlane(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, float transparency, float colorR /*= 0.5f*/, float colorG /*= 0.5f*/, float colorB /*= 0.5f*/) + VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createPlane(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, const Color& color) { - SoSeparator* res = CreatePlaneVisualization(position, normal, extend, transparency, false, colorR, colorG, colorB); + SoSeparator* res = CreatePlaneVisualization(position, normal, extend, false, color); VisualizationNodePtr node(new CoinVisualizationNode(res)); return node; } - SoSeparator* CoinVisualizationFactory::CreatePlaneVisualization(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, float transparency, bool grid, float colorR /*= 0.5f*/, float colorG /*= 0.5f*/, float colorB /*= 0.5f*/, std::string textureFile) + SoSeparator* CoinVisualizationFactory::CreatePlaneVisualization(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, bool grid, const Color& color, std::string textureFile) { SoSeparator* res = new SoSeparator(); res->ref(); @@ -1206,9 +1191,9 @@ namespace VirtualRobot // Set material SoMaterial* m = new SoMaterial; - m->transparency.setValue(transparency); - m->diffuseColor.setValue(colorR, colorG, colorB); - m->ambientColor.setValue(colorR, colorG, colorB); + m->transparency.setValue(color.transparency); + m->diffuseColor.setValue(color.r, color.g, color.b); + m->ambientColor.setValue(color.r, color.g, color.b); res->addChild(m); if (grid) @@ -1217,21 +1202,21 @@ namespace VirtualRobot if (!textureFile.empty() && RuntimeEnvironment::getDataFileAbsolute(textureFile)) { - res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, textureFile.c_str(), transparency); + res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, textureFile.c_str(), color.transparency); } else { - if (transparency == 0) + if (color.transparency == 0) { std::string filename("images/FloorWhite.png"); RuntimeEnvironment::getDataFileAbsolute(filename); - res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, filename.c_str(), transparency); + res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, filename.c_str(), color.transparency); } else { std::string filename("images/Floor.png"); RuntimeEnvironment::getDataFileAbsolute(filename); - res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, filename.c_str(), transparency); + res2 = CreateGrid(extend, extend, extend / 500.0f, extend / 500.0f, true, filename.c_str(), color.transparency); } } @@ -1301,7 +1286,7 @@ namespace VirtualRobot return pGrid; } - SoSeparator* CoinVisualizationFactory::CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::Color colorInner, VisualizationFactory::Color colorLine, float lineSize) + SoSeparator* CoinVisualizationFactory::CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points,const Color& colorInner,const Color& colorLine, float lineSize) { VisualizationFactory::PhongMaterial mat; mat.diffuse = colorInner; @@ -1311,7 +1296,7 @@ namespace VirtualRobot return CreatePolygonVisualization(points, mat, colorLine, lineSize); } - SoSeparator* CoinVisualizationFactory::CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::PhongMaterial mat, VisualizationFactory::Color colorLine, float lineSize) + SoSeparator* CoinVisualizationFactory::CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::PhongMaterial mat,const Color& colorLine, float lineSize) { SoSeparator* visu = new SoSeparator; @@ -1380,7 +1365,7 @@ namespace VirtualRobot } - SoSeparator* CoinVisualizationFactory::CreateConvexHull2DVisualization(const MathTools::ConvexHull2DPtr ch, MathTools::Plane& p, VisualizationFactory::Color colorInner /*= VisualizationFactory::Color::Blue()*/, VisualizationFactory::Color colorLine /*= VisualizationFactory::Color::Black()*/, float lineSize /*= 5.0f*/, const Eigen::Vector3f& offset /*=Eigen::Vector3f::Zero() */) + SoSeparator* CoinVisualizationFactory::CreateConvexHull2DVisualization(const MathTools::ConvexHull2DPtr ch, MathTools::Plane& p,const Color& colorInner /*= Color::Blue()*/,const Color& colorLine /*= Color::Black()*/, float lineSize /*= 5.0f*/, const Eigen::Vector3f& offset /*=Eigen::Vector3f::Zero() */) { if (!ch) { @@ -1866,7 +1851,7 @@ namespace VirtualRobot } - SoNode* CoinVisualizationFactory::getCoinVisualization(TriMeshModelPtr model, bool showNormals, VisualizationFactory::Color color, bool showLines) + SoNode* CoinVisualizationFactory::getCoinVisualization(TriMeshModelPtr model, bool showNormals,const Color& color, bool showLines) { SoSeparator* res = new SoSeparator; res->ref(); @@ -1878,11 +1863,11 @@ namespace VirtualRobot SoSeparator* arrow = CreateArrow(z, 30.0f, 1.5f); arrow->ref(); float lineSize = 4.0f; - VisualizationFactory::Color lineColor = VisualizationFactory::Color::Black(); + Color lineColor = Color::Black(); if (!showLines) { - lineColor = VisualizationFactory::Color::None(); + lineColor = Color::None(); lineSize = 0.0f; } @@ -1899,7 +1884,7 @@ namespace VirtualRobot v.push_back(v3); // SoSeparator* s = CreatePolygonVisualization(v,color,lineColor,lineSize); - VisualizationFactory::Color triColor = (model->colors.size() == 0) ? color : model->colors[model->faces[i].idColor1]; + const Color& triColor = model->colors.empty() ? color : model->colors[model->faces[i].idColor1]; SoSeparator* s; @@ -2254,7 +2239,7 @@ namespace VirtualRobot VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createTriMeshModelVisualization(const TriMeshModelPtr& model, bool showNormals, const Eigen::Matrix4f& pose, bool showLines) { SoSeparator* res = new SoSeparator; - SoNode* res1 = CoinVisualizationFactory::getCoinVisualization(model, showNormals, VisualizationFactory::Color::Gray(), showLines); + SoNode* res1 = CoinVisualizationFactory::getCoinVisualization(model, showNormals, Color::Gray(), showLines); SoMatrixTransform* mt = getMatrixTransformScaleMM2M(pose); res->addChild(mt); res->addChild(res1); @@ -2324,10 +2309,7 @@ namespace VirtualRobot float radius, float tubeRadius, float completion, - float colorR, - float colorG, - float colorB, - float transparency, + const Color& color, int #ifndef NDEBUG sides @@ -2346,7 +2328,7 @@ namespace VirtualRobot { torusCompletion = 0; } - auto torusNode = createTorus(radius, tubeRadius, torusCompletion, colorR, colorG, colorB, transparency); + auto torusNode = createTorus(radius, tubeRadius, torusCompletion, color); SoNode* torus = std::dynamic_pointer_cast<CoinVisualizationNode>(torusNode)->getCoinVisualization(); SoSeparator* s = new SoSeparator(); @@ -2357,8 +2339,8 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); s->addChild(torus); @@ -2376,7 +2358,7 @@ namespace VirtualRobot tr->rotation.setValue(SbVec3f(0, 0, 1), angle1); subSep->addChild(tr); - subSep->addChild(CreateArrow(Eigen::Vector3f::UnitY()*sign, 0, tubeRadius, Color(colorR, colorG, colorB))); + subSep->addChild(CreateArrow(Eigen::Vector3f::UnitY()*sign, 0, tubeRadius, Color(color.r, color.g, color.b))); VisualizationNodePtr node(new CoinVisualizationNode(s)); @@ -2384,7 +2366,7 @@ namespace VirtualRobot return node; } - VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createTrajectory(TrajectoryPtr t, Color colorNode, Color colorLine, float nodeSize, float lineSize) + VirtualRobot::VisualizationNodePtr CoinVisualizationFactory::createTrajectory(TrajectoryPtr t,const Color& colorNode,const Color& colorLine, float nodeSize, float lineSize) { SoNode* res = getCoinVisualization(t, colorNode, colorLine, nodeSize, lineSize); @@ -2394,7 +2376,7 @@ namespace VirtualRobot //#define TEST_SHOW_VOXEL - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, int a, int b, int c, /*const Eigen::Vector3f &positionGlobal,*/ int nrBestEntries, SoSeparator* arrow, const VirtualRobot::ColorMap& cm, bool transformToGlobalPose, unsigned char /*minValue*/) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, int a, int b, int c, /*const Eigen::Vector3f &positionGlobal,*/ int nrBestEntries, SoSeparator* arrow, const ColorMap& cm, bool transformToGlobalPose, unsigned char /*minValue*/) { if (!reachSpace || reachSpace->numVoxels[0] <= 0 || reachSpace->numVoxels[1] <= 0 || reachSpace->numVoxels[2] <= 0) @@ -2472,7 +2454,7 @@ namespace VirtualRobot SoUnits* u = new SoUnits(); u->units = SoUnits::METERS; res->addChild(u); - VirtualRobot::VisualizationFactory::Color color = VirtualRobot::VisualizationFactory::Color::None(); + Color color = Color::None(); std::map< unsigned char, std::vector<Eigen::Vector3f> >::reverse_iterator i = entryRot.rbegin(); int nr = 0; float x[6]; @@ -2726,7 +2708,7 @@ namespace VirtualRobot return res; } - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, const Eigen::Vector3f& fixedEEFOrientationGlobalRPY, VirtualRobot::ColorMap cm, bool transformToGlobalPose, const Eigen::Vector3f& axis, unsigned char minValue, float arrowSize) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, const Eigen::Vector3f& fixedEEFOrientationGlobalRPY, ColorMap cm, bool transformToGlobalPose, const Eigen::Vector3f& axis, unsigned char minValue, float arrowSize) { SoSeparator* res = new SoSeparator; res->ref(); @@ -2780,7 +2762,7 @@ namespace VirtualRobot //Eigen::Vector3f zAxis(0,0,1.0f); int value; - VirtualRobot::VisualizationFactory::Color color = VirtualRobot::VisualizationFactory::Color::None(); + Color color = Color::None(); SoSeparator* arrow = CreateArrow(axis, minS * 0.75f, minS / 20.0f, color); if (minValue <= 0) @@ -2861,7 +2843,7 @@ namespace VirtualRobot return res; } - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, VirtualRobot::ColorMap cm, const Eigen::Vector3f& axis, bool transformToGlobalPose, unsigned char minValue, float arrowSize, int nrRotations) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, ColorMap cm, const Eigen::Vector3f& axis, bool transformToGlobalPose, unsigned char minValue, float arrowSize, int nrRotations) { SoSeparator* res = new SoSeparator; res->ref(); @@ -2893,7 +2875,7 @@ namespace VirtualRobot minS = arrowSize; } - VirtualRobot::VisualizationFactory::Color color = VirtualRobot::VisualizationFactory::Color::None(); + Color color = Color::None(); SoSeparator* arrow = CreateArrow(axis, minS * 0.7f, minS / 25.0f, color); Eigen::Vector3f voxelPosition; @@ -2931,7 +2913,7 @@ namespace VirtualRobot return res; } - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, const VirtualRobot::ColorMap cm, bool transformToGlobalPose, float maxZGlobal, float minAngle, float maxAngle) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentationPtr reachSpace, const ColorMap cm, bool transformToGlobalPose, float maxZGlobal, float minAngle, float maxAngle) { SoSeparator* res = new SoSeparator; res->ref(); @@ -2959,7 +2941,7 @@ namespace VirtualRobot } - VirtualRobot::VisualizationFactory::Color color = VirtualRobot::VisualizationFactory::Color::None(); + Color color = Color::None(); float radius = minS * 0.5f * 0.75f; Eigen::Vector3f voxelPosition; int maxValue = reachSpace->getMaxSummedAngleReachablity(); @@ -3018,7 +3000,7 @@ namespace VirtualRobot color = cm.getColor(intensity); - SoNode* n = CreateVertexVisualization(resPos, radius, color.transparency, color.r, color.g, color.b); + SoNode* n = CreateVertexVisualization(resPos, radius, color); if (n) { @@ -3033,7 +3015,7 @@ namespace VirtualRobot return res; } - SoNode* CoinVisualizationFactory::getCoinVisualization(TrajectoryPtr t, Color colorNode, Color colorLine, float nodeSize, float lineSize) + SoNode* CoinVisualizationFactory::getCoinVisualization(TrajectoryPtr t,const Color& colorNode,const Color& colorLine, float nodeSize, float lineSize) { SoSeparator* res = new SoSeparator; @@ -3132,7 +3114,7 @@ namespace VirtualRobot return res; } - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceGridPtr reachGrid, VirtualRobot::ColorMap cm, bool /*transformToGlobalPose*/ /*= true*/) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceGridPtr reachGrid, ColorMap cm, bool /*transformToGlobalPose*/ /*= true*/) { SoSeparator* res = new SoSeparator; @@ -3217,7 +3199,7 @@ namespace VirtualRobot intensity = 1.0f; } - VirtualRobot::VisualizationFactory::Color color = cm.getColor(intensity); + Color color = cm.getColor(intensity); SoMaterial* mat = new SoMaterial(); @@ -3256,7 +3238,7 @@ namespace VirtualRobot } - SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentation::WorkspaceCut2DPtr cutXY, VirtualRobot::ColorMap cm, const Eigen::Vector3f& normal, float maxEntry, float minAngle, float maxAngle) + SoNode* CoinVisualizationFactory::getCoinVisualization(WorkspaceRepresentation::WorkspaceCut2DPtr cutXY, ColorMap cm, const Eigen::Vector3f& normal, float maxEntry, float minAngle, float maxAngle) { SoSeparator* res = new SoSeparator; @@ -3362,7 +3344,7 @@ namespace VirtualRobot intensity = 1.0f; } - VirtualRobot::VisualizationFactory::Color color = cm.getColor(intensity); + Color color = cm.getColor(intensity); SoMaterial* mat = new SoMaterial(); @@ -3402,7 +3384,7 @@ namespace VirtualRobot - SoSeparator* CoinVisualizationFactory::Create2DMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, const VirtualRobot::ColorMap cm, bool drawZeroCells, bool drawLines) + SoSeparator* CoinVisualizationFactory::Create2DMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, const ColorMap cm, bool drawZeroCells, bool drawLines) { SoSeparator* res = new SoSeparator; res->ref(); @@ -3483,7 +3465,7 @@ namespace VirtualRobot intensity = 1.0f; } - VirtualRobot::VisualizationFactory::Color color = cm.getColor(intensity); + Color color = cm.getColor(intensity); SoMaterial* mat = new SoMaterial(); @@ -3523,7 +3505,7 @@ namespace VirtualRobot return res; } - SoSeparator* CoinVisualizationFactory::Create2DHeightMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, float heightZ, const VirtualRobot::ColorMap cm, bool drawZeroCells, bool drawLines) + SoSeparator* CoinVisualizationFactory::Create2DHeightMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, float heightZ, const ColorMap cm, bool drawZeroCells, bool drawLines) { SoSeparator* res = new SoSeparator; res->ref(); @@ -3621,7 +3603,7 @@ namespace VirtualRobot if (drawZeroCells || intensity > 0.) { float lineWidth = drawLines ? 4.0f : 0.f; - SoSeparator* pol = CreatePolygonVisualization(pts, cm.getColor(intensity), VisualizationFactory::Color::Black(), lineWidth); + SoSeparator* pol = CreatePolygonVisualization(pts, cm.getColor(intensity), Color::Black(), lineWidth); grid->addChild(pol); } } @@ -3632,7 +3614,7 @@ namespace VirtualRobot return res; } - SoSeparator* CoinVisualizationFactory::Colorize(SoNode* model, VisualizationFactory::Color c) + SoSeparator* CoinColorize(SoNode* model, const CoinVisualizationFactory::Color& c) { SoSeparator* result = new SoSeparator; SoBaseColor* bc = new SoBaseColor(); @@ -4131,7 +4113,7 @@ namespace VirtualRobot } } - SoSeparator* CoinVisualizationFactory::CreateOOBBVisualization(const MathTools::OOBB& oobb, Color colorLine /*= Color::Gray()*/, float lineSize /*= 4.0f*/) + SoSeparator* CoinVisualizationFactory::CreateOOBBVisualization(const MathTools::OOBB& oobb,const Color& colorLine /*= Color::Gray()*/, float lineSize /*= 4.0f*/) { SoSeparator* res = new SoSeparator; res->ref(); @@ -4150,7 +4132,7 @@ namespace VirtualRobot return res; } - SoSeparator* CoinVisualizationFactory::CreateSegmentVisualization(const MathTools::Segment& s, Color colorLine /*= Color::Gray()*/, float lineSize /*= 4.0f*/) + SoSeparator* CoinVisualizationFactory::CreateSegmentVisualization(const MathTools::Segment& s,const Color& colorLine /*= Color::Gray()*/, float lineSize /*= 4.0f*/) { SoSeparator* res = new SoSeparator; res->ref(); @@ -4161,6 +4143,8 @@ namespace VirtualRobot SoMaterial* materialLineSolution = new SoMaterial(); materialLineSolution->ambientColor.setValue(colorLine.r, colorLine.g, colorLine.b); materialLineSolution->diffuseColor.setValue(colorLine.r, colorLine.g, colorLine.b); + materialLineSolution->transparency.setValue(colorLine.transparency); + SoDrawStyle* lineSolutionStyle = new SoDrawStyle(); lineSolutionStyle->lineWidth.setValue(lineSize); @@ -4304,24 +4288,18 @@ namespace VirtualRobot SoSeparator* CoinVisualizationFactory::CreateSphere( float radius, - float colorR, - float colorG, - float colorB) + const Color& color) { return CreateSphere( Eigen::Vector3f::Zero(), radius, - colorR, - colorG, - colorB); + color); } SoSeparator* CoinVisualizationFactory::CreateSphere( const Eigen::Vector3f& p, float radius, - float colorR, - float colorG, - float colorB) + const Color& color) { SoSeparator* s = new SoSeparator(); s->ref(); @@ -4337,8 +4315,9 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); s->addChild(m); - m->ambientColor.setValue(colorR, colorG, colorB); - m->diffuseColor.setValue(colorR, colorG, colorB); + m->ambientColor.setValue(color.r, color.g, color.b); + m->diffuseColor.setValue(color.r, color.g, color.b); + m->transparency.setValue(color.transparency); SoSphere* c = new SoSphere(); s->addChild(c); @@ -4504,6 +4483,7 @@ namespace VirtualRobot SoMaterial* m = new SoMaterial(); m->ambientColor.setValue(color.r, color.g, color.b); m->diffuseColor.setValue(color.r, color.g, color.b); + m->transparency.setValue(color.transparency); return m; } diff --git a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h index eaf8b1878e4eedb63547d6a51ba0eb7ed899396f..c829659b48865dd387f45defd52cd729788ba780 100644 --- a/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h +++ b/VirtualRobot/Visualization/CoinVisualization/CoinVisualizationFactory.h @@ -31,6 +31,7 @@ #include "../ColorMap.h" #include "../../Workspace/WorkspaceRepresentation.h" +#include "SimoxUtility/color/Color.h" #include <Inventor/SoInput.h> #include <Inventor/nodes/SoMatrixTransform.h> #include <Inventor/nodes/SoMaterial.h> @@ -66,36 +67,34 @@ namespace VirtualRobot void init(int& argc, char* argv[], const std::string& appName) override; - VisualizationNodePtr getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& primitives, bool boundingBox = false, Color color = Color::Gray()) override; + VisualizationNodePtr getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& primitives, bool boundingBox = false,const Color& color = Color::Gray()) override; VisualizationNodePtr getVisualizationFromFile(const std::string& filename, bool boundingBox = false, float scaleX = 1.0f, float scaleY = 1.0f, float scaleZ = 1.0f) override; virtual VisualizationNodePtr getVisualizationFromFileWithAssimp(const std::string& filename, bool boundingBox = false, float scaleX = 1.0f, float scaleY = 1.0f, float scaleZ = 1.0f); virtual VisualizationNodePtr getVisualizationFromCoin3DFile(const std::string& filename, bool boundingBox = false); VisualizationNodePtr getVisualizationFromFile(const std::ifstream& ifs, bool boundingBox = false, float scaleX = 1.0f, float scaleY = 1.0f, float scaleZ = 1.0f) override; virtual VisualizationNodePtr getVisualizationFromString(const std::string& modelString, bool boundingBox = false); - - virtual VisualizationPtr getVisualization(const std::vector<VisualizationNodePtr>& visus); virtual VisualizationPtr getVisualization(VisualizationNodePtr visu); - - VisualizationNodePtr createBox(float width, float height, float depth, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; - VisualizationNodePtr createLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width = 1.0f, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; - VisualizationNodePtr createLine(const Eigen::Matrix4f& from, const Eigen::Matrix4f& to, float width = 1.0f, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; - VisualizationNodePtr createSphere(float radius, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; - VisualizationNodePtr createCylinder(float radius, float height, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; - VisualizationNodePtr createCircle(float radius, float circleCompletion, float width, float colorR = 1.0f, float colorG = 0.5f, float colorB = 0.5f, size_t numberOfCircleParts = 30) override; + VisualizationNodePtr createBox(float width, float height, float depth, const Color& color = Color::Gray()) override; + VisualizationNodePtr createLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width = 1.0f, const Color& color = Color::Gray()) override; + VisualizationNodePtr createSphere(float radius, const Color& color = Color::Gray()) override; + VisualizationNodePtr createCylinder(float radius, float height, const Color& color = Color::Gray()) override; + VisualizationNodePtr createCircle(float radius, float circleCompletion, float width, const Color& color = Color::Gray(), size_t numberOfCircleParts = 30) override; VisualizationNodePtr createCoordSystem(float scaling = 1.0f, std::string* text = NULL, float axisLength = 100.0f, float axisSize = 3.0f, int nrOfBlocks = 10) override; VisualizationNodePtr createBoundingBox(const BoundingBox& bbox, bool wireFrame = false) override; - VisualizationNodePtr createVertexVisualization(const Eigen::Vector3f& position, float radius, float transparency, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; + VisualizationNodePtr createVertexVisualization(const Eigen::Vector3f& position, float radius, const Color& color = Color::Gray()) override; VisualizationNodePtr createTriMeshModelVisualization(const TriMeshModelPtr& model, const Eigen::Matrix4f& pose = Eigen::Matrix4f::Identity(), float scaleX = 1.0f, float scaleY = 1.0f, float scaleZ = 1.0f) override; VisualizationNodePtr createTriMeshModelVisualization(const TriMeshModelPtr& model, bool showNormals, const Eigen::Matrix4f& pose, bool showLines = true) override; - VisualizationNodePtr createPlane(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, float transparency, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) override; + VisualizationNodePtr createPlane(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, const Color& color = Color::Gray()) override; VisualizationNodePtr createArrow(const Eigen::Vector3f& n, float length = 50.0f, float width = 2.0f, const Color& color = Color::Gray()) override; - VisualizationNodePtr createCircleArrow(float radius, float tubeRadius, float completion = 1, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f, float transparency = 0.0f, int sides = 8, int rings = 30) override; - VisualizationNodePtr createTrajectory(TrajectoryPtr t, Color colorNode = Color::Blue(), Color colorLine = Color::Gray(), float nodeSize = 15.0f, float lineSize = 4.0f) override; - VisualizationNodePtr createText(const std::string& text, bool billboard = false, float scaling = 1.0f, Color c = Color::Black(), float offsetX = 20.0f, float offsetY = 20.0f, float offsetZ = 0.0f) override; - VisualizationNodePtr createTorus(float radius, float tubeRadius, float completion = 1, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f, float transparency = 0.0f, int sides = 8, int rings = 30) override; + VisualizationNodePtr createCircleArrow(float radius, float tubeRadius, float completion = 1, const Color& color = Color::Gray(), int sides = 8, int rings = 30) override; + VisualizationNodePtr createTrajectory(TrajectoryPtr t, const Color& colorNode = Color::Blue(),const Color& colorLine = Color::Gray(), float nodeSize = 15.0f, float lineSize = 4.0f) override; + VisualizationNodePtr createText(const std::string& text, bool billboard = false, float scaling = 1.0f, const Color& c = Color::Black(), float offsetX = 20.0f, float offsetY = 20.0f, float offsetZ = 0.0f) override; + VisualizationNodePtr createTorus(float radius, float tubeRadius, float completion = 1, const Color& color = Color::Gray(), int sides = 8, int rings = 30) override; + + /*! Creates an coordinate axis aligned ellipse \param x The extend in x direction must be >= 1e-6 @@ -120,10 +119,10 @@ namespace VirtualRobot VisualizationNodePtr createUnitedVisualization(const std::vector<VisualizationNodePtr>& visualizations) const override; - static SoSeparator* CreateConvexHull2DVisualization(const MathTools::ConvexHull2DPtr ch, MathTools::Plane& p, VisualizationFactory::Color colorInner = VisualizationFactory::Color::Blue(), VisualizationFactory::Color colorLine = VisualizationFactory::Color::Black(), float lineSize = 5.0f, const Eigen::Vector3f& offset = Eigen::Vector3f::Zero()); - static SoSeparator* CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::Color colorInner = VisualizationFactory::Color::Blue(), VisualizationFactory::Color colorLine = VisualizationFactory::Color::Black(), float lineSize = 4.0f); - static SoSeparator* CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::PhongMaterial mat, VisualizationFactory::Color colorLine = VisualizationFactory::Color::Black(), float lineSize = 4.0f); - static SoSeparator* CreatePlaneVisualization(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, float transparency, bool grid = true, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f, std::string textureFile = std::string()); + static SoSeparator* CreateConvexHull2DVisualization(const MathTools::ConvexHull2DPtr ch, MathTools::Plane& p,const Color& colorInner = Color::Blue(),const Color& colorLine = Color::Black(), float lineSize = 5.0f, const Eigen::Vector3f& offset = Eigen::Vector3f::Zero()); + static SoSeparator* CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points,const Color& colorInner = Color::Blue(),const Color& colorLine = Color::Black(), float lineSize = 4.0f); + static SoSeparator* CreatePolygonVisualization(const std::vector<Eigen::Vector3f>& points, VisualizationFactory::PhongMaterial mat,const Color& colorLine = Color::Black(), float lineSize = 4.0f); + static SoSeparator* CreatePlaneVisualization(const Eigen::Vector3f& position, const Eigen::Vector3f& normal, float extend, bool grid = true, const Color& color = Color::Gray(), std::string textureFile = std::string()); static SoSeparator* CreateCoordSystemVisualization(float scaling = 1.0f, std::string* text = NULL, float axisLength = 100.0f, float axisSize = 3.0f, int nrOfBlocks = 10); static SoSeparator* CreateBoundingBox(SoNode* ivModel, bool wireFrame = false); static SoSeparator* CreateGrid(float width, float depth, float widthMosaic, float depthMosaic, bool InvertNormal, const char* pFileName, float Transparency); @@ -132,8 +131,8 @@ namespace VirtualRobot static SoSeparator* CreatePointsVisualization(const std::vector<MathTools::ContactPoint>& points, bool showNormals = false); static SoSeparator* CreateArrow(const Eigen::Vector3f& pt, const Eigen::Vector3f& n, float length = 50.0f, float width = 2.0f, const Color& color = Color::Gray()); static SoSeparator* CreateArrow(const Eigen::Vector3f& n, float length = 50.0f, float width = 2.0f, const Color& color = Color::Gray()); - static SoSeparator* CreateVertexVisualization(const Eigen::Vector3f& position, float radius, float transparency, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f); - static SoSeparator* CreateVerticesVisualization(const std::vector<Eigen::Vector3f>& positions, float radius, VisualizationFactory::Color color = VisualizationFactory::Color::Gray()); + static SoSeparator* CreateVertexVisualization(const Eigen::Vector3f& position, float radius, const Color& color = Color::Gray()); + static SoSeparator* CreateVerticesVisualization(const std::vector<Eigen::Vector3f>& positions, float radius,const Color& color = Color::Gray()); static void RemoveDuplicateTextures(SoNode* node, const std::string& currentPath); /*! @@ -161,28 +160,24 @@ namespace VirtualRobot ); static SoSeparator* CreateSphere(float radius, - float colorR, - float colorG, - float colorB); + const Color& color); static SoSeparator* CreateSphere(const Eigen::Vector3f& p, float radius, - float colorR, - float colorG, - float colorB); + const Color& color); static SoSeparator* CreateCylindroid(float axisLengthX, float axisLengthY, float height, SoMaterial* matBody = nullptr); static SoSeparator* Create2DMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, const VirtualRobot::ColorMap cm = VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), bool drawZeroCells = false, bool drawLines = true); static SoSeparator* Create2DHeightMap(const Eigen::MatrixXf& d, float extendCellX, float extendCellY, float heightZ, const VirtualRobot::ColorMap cm = VirtualRobot::ColorMap(VirtualRobot::ColorMap::eHot), bool drawZeroCells = false, bool drawLines = true); - static SoSeparator* CreateOOBBVisualization(const MathTools::OOBB& oobb, Color colorLine = Color::Gray(), float lineSize = 4.0f); - static SoSeparator* CreateSegmentVisualization(const MathTools::Segment& s, Color colorLine = Color::Gray(), float lineSize = 4.0f); + static SoSeparator* CreateOOBBVisualization(const MathTools::OOBB& oobb,const Color& colorLine = Color::Gray(), float lineSize = 4.0f); + static SoSeparator* CreateSegmentVisualization(const MathTools::Segment& s,const Color& colorLine = Color::Gray(), float lineSize = 4.0f); /*! Creates a colored model, by creating a new SoSeparator and adding a basecolor with overide flags followed by the model. */ - static SoSeparator* Colorize(SoNode* model, VisualizationFactory::Color c); + static SoSeparator* Colorize(SoNode* model,const Color& c); static SbMatrix getSbMatrix(const Eigen::Matrix4f& m); static SbMatrix getSbMatrixVec(const Eigen::Vector3f& m); @@ -246,10 +241,10 @@ namespace VirtualRobot static SoNode* getCoinVisualization(VisualizationNodePtr visu); static SoNode* getCoinVisualization(TriMeshModelPtr model); - static SoNode* getCoinVisualization(TriMeshModelPtr model, bool shownormals, VisualizationFactory::Color color = VisualizationFactory::Color::Gray(), bool showLines = true); + static SoNode* getCoinVisualization(TriMeshModelPtr model, bool shownormals,const Color& color = Color::Gray(), bool showLines = true); - static SoNode* getCoinVisualization(TrajectoryPtr t, Color colorNode = Color::Blue(), Color colorLine = Color::Gray(), float nodeSize = 15.0f, float lineSize = 4.0f); + static SoNode* getCoinVisualization(TrajectoryPtr t,const Color& colorNode = Color::Blue(),const Color& colorLine = Color::Gray(), float nodeSize = 15.0f, float lineSize = 4.0f); /*! Create a visualization of the reachability data. */ @@ -282,8 +277,8 @@ namespace VirtualRobot \param m The pose with translation given in millimeter. */ static SoMatrixTransform* getMatrixTransformScaleMM2M(const Eigen::Matrix4f& m); - static SoNode* createCoinLine(const Eigen::Matrix4f& from, const Eigen::Matrix4f& to, float width, float colorR, float colorG, float colorB); - static SoNode* createCoinPartCircle(float radius, float circleCompletion, float width, float colorR, float colorG, float colorB, size_t numberOfCircleParts, float offset=0); + static SoNode* createCoinLine(const Eigen::Vector3f& from, const Eigen::Vector3f& to, float width, const Color& color); + static SoNode* createCoinPartCircle(float radius, float circleCompletion, float width, const Color& color, size_t numberOfCircleParts, float offset=0); /*! @@ -448,7 +443,7 @@ namespace VirtualRobot */ void cleanup() override; protected: - static SoNode* GetNodeFromPrimitive(Primitive::PrimitivePtr primitive, bool boundingBox, Color color); + static SoNode* GetNodeFromPrimitive(Primitive::PrimitivePtr primitive, bool boundingBox,const Color& color); static void GetVisualizationFromSoInput(SoInput& soInput, VisualizationNodePtr& visualizationNode, bool bbox = false, bool freeDuplicateTextures = true); static inline char IVToolsHelper_ReplaceSpaceWithUnderscore(char input) @@ -478,4 +473,3 @@ namespace VirtualRobot } // namespace VirtualRobot - diff --git a/VirtualRobot/Visualization/VisualizationFactory.cpp b/VirtualRobot/Visualization/VisualizationFactory.cpp index 26cfa61e5fdefefbf0cf719f3cb9354bbd8079fe..5a7fa08a215b02f22294fac6c1399276f52341e0 100644 --- a/VirtualRobot/Visualization/VisualizationFactory.cpp +++ b/VirtualRobot/Visualization/VisualizationFactory.cpp @@ -23,4 +23,148 @@ namespace VirtualRobot } + VisualizationNodePtr + VisualizationFactory::createBox(float /*width*/, + float /*height*/, + float /*depth*/, + const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createLine(const Eigen::Vector3f& /*from*/, + const Eigen::Vector3f& /*to*/, + float /*width*/, + const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createSphere(float /*radius*/, const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createCylinder(float /*radius*/, float /*height*/, const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createCircle(float /*radius*/, + float /*circleCompletion*/, + float /*width*/, + const Color& /*color*/, + size_t /*numberOfCircleParts*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createVertexVisualization(const Eigen::Vector3f& /*position*/, + float /*radius*/, + const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createPlane(const Eigen::Vector3f& /*position*/, + const Eigen::Vector3f& /*normal*/, + float /*extend*/, + const Color& /*color*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createCircleArrow(float /*radius*/, + float /*tubeRadius*/, + float /*completion*/, + const Color& /*color*/, + int /*sides*/, + int /*rings*/) + { + return nullptr; + } + + + VisualizationNodePtr + VisualizationFactory::createTorus(float /*radius*/, + float /*tubeRadius*/, + float /*completion*/, + const Color& /*color*/, + int /*sides*/, + int /*rings*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createTrajectory(TrajectoryPtr /*t*/, + const Color& /*colorNode*/, + const Color& /*colorLine*/, + float /*nodeSize*/, + float /*lineSize*/) + { + return nullptr; + } + VisualizationNodePtr + VisualizationFactory::createText(const std::string& /*text*/, + bool /*billboard*/, + float /*scaling*/, + const Color& /*c*/, + float /*offsetX*/, + float /*offsetY*/, + float /*offsetZ*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createTriMeshModelVisualization(const TriMeshModelPtr& /*model*/, + const Eigen::Matrix4f& /*pose*/, + float /*scaleX*/, + float /*scaleY*/, + float /*scaleZ*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createTriMeshModelVisualization(const TriMeshModelPtr& /*model*/, + bool /*showNormals*/, + const Eigen::Matrix4f& /*pose*/, + bool /*showLines*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createBoundingBox(const BoundingBox& /*bbox*/, bool /*wireFrame*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createCoordSystem(float /*scaling*/, + std::string* /*text*/, + float /*axisLength*/, + float /*axisSize*/, + int /*nrOfBlocks*/) + { + return nullptr; + } + + VisualizationNodePtr + VisualizationFactory::createArrow(const Eigen::Vector3f& /*n*/, + float /*length*/, + float /*width*/, + const Color& /*color*/) + { + return nullptr; + } } // namespace VirtualRobot diff --git a/VirtualRobot/Visualization/VisualizationFactory.h b/VirtualRobot/Visualization/VisualizationFactory.h index 537731321099954000d1609bc441a52d927eee8b..3e038dc235ceef9e4d6670c8a9f0a9a0debf07df 100644 --- a/VirtualRobot/Visualization/VisualizationFactory.h +++ b/VirtualRobot/Visualization/VisualizationFactory.h @@ -27,6 +27,7 @@ #include "../MathTools.h" #include "../BoundingBox.h" #include "../Primitive.h" +#include "SimoxUtility/color/Color.h" #include <Eigen/Core> #include <string> @@ -73,6 +74,8 @@ namespace VirtualRobot { return Color(0.0f, 0.0f, 0.0f, 1.0f); } + + Color(const simox::Color& sc): Color(sc.r / 255., sc.g / 255., sc.b / 255., sc.a / 255.){} }; struct PhongMaterial @@ -97,7 +100,7 @@ namespace VirtualRobot { } - virtual VisualizationNodePtr getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& /*primitives*/, bool /*boundingBox*/ = false, Color /*color*/ = Color::Gray()) + virtual VisualizationNodePtr getVisualizationFromPrimitives(const std::vector<Primitive::PrimitivePtr>& /*primitives*/, bool /*boundingBox*/ = false, const Color& /*color*/ = Color::Gray()) { return nullptr; } @@ -109,86 +112,96 @@ namespace VirtualRobot { return nullptr; } - /*! - A box, dimensions are given in mm. - */ - virtual VisualizationNodePtr createBox(float /*width*/, float /*height*/, float /*depth*/, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createLine(const Eigen::Vector3f& /*from*/, const Eigen::Vector3f& /*to*/, float /*width*/ = 1.0f, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createLine(const Eigen::Matrix4f& /*from*/, const Eigen::Matrix4f& /*to*/, float /*width*/ = 1.0f, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createSphere(float /*radius*/, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createCircle(float /*radius*/, float /*circleCompletion*/, float /*width*/, float /*colorR*/ = 1.0f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f, size_t /*numberOfCircleParts*/ = 30) - { - return nullptr; - } - - virtual VisualizationNodePtr createTorus(float /*radius*/, float /*tubeRadius*/, float /*completion*/ = 1.0f, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f, float /*transparency*/ = 0.0f, int /*sides*/ = 8, int /*rings*/ = 30) - { - return nullptr; - } + + // virtual VisualizationNodePtr createPlane(const MathTools::Plane& plane, float extend, float transparency, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) + // { + // return createPlane(plane.p, plane.n, extend, transparency, colorR, colorG, colorB); + // } + + + + virtual VisualizationNodePtr + createBox(float width, float height, float depth, const Color& color = Color::Gray()); + + virtual VisualizationNodePtr createLine(const Eigen::Vector3f& from, + const Eigen::Vector3f& to, + float width = 1.0f, + const Color& color = Color::Gray()); + + virtual VisualizationNodePtr createSphere(float radius, const Color& color = Color::Gray()); + + virtual VisualizationNodePtr + createCylinder(float radius, float height, const Color& color = Color::Gray()); + + virtual VisualizationNodePtr createCircle(float radius, + float circleCompletion, + float width, + const Color& color = Color::Gray(), + size_t numberOfCircleParts = 30); + + virtual VisualizationNodePtr createCoordSystem(float /*scaling*/ = 1.0f, + std::string* text = nullptr, + float axisLength = 100.0f, + float axisSize = 3.0f, + int nrOfBlocks = 10); + + virtual VisualizationNodePtr createBoundingBox(const BoundingBox& bbox, + bool wireFrame = false); + + virtual VisualizationNodePtr createVertexVisualization(const Eigen::Vector3f& position, + float radius, + const Color& color = Color::Gray()); + + virtual VisualizationNodePtr + createTriMeshModelVisualization(const TriMeshModelPtr& model, + const Eigen::Matrix4f& pose = Eigen::Matrix4f::Identity(), + float scaleX = 1.0f, + float scaleY = 1.0f, + float scaleZ = 1.0f); + + virtual VisualizationNodePtr createTriMeshModelVisualization(const TriMeshModelPtr& model, + bool showNormals, + const Eigen::Matrix4f& pose, + bool /*showLines*/ = true); + + virtual VisualizationNodePtr createPlane(const Eigen::Vector3f& position, + const Eigen::Vector3f& normal, + float extend, + const Color& color = Color::Gray()); + + virtual VisualizationNodePtr createArrow(const Eigen::Vector3f& n, + float length = 50.0f, + float width = 2.0f, + const Color& color = Color::Gray()); + + virtual VisualizationNodePtr createCircleArrow(float radius, + float tubeRadius, + float completion = 1, + const Color& color = Color::Gray(), + int sides = 8, + int rings = 30); + + virtual VisualizationNodePtr createTrajectory(TrajectoryPtr t, + const Color& colorNode = Color::Blue(), + const Color& colorLine = Color::Gray(), + float nodeSize = 15.0f, + float lineSize = 4.0f); + + virtual VisualizationNodePtr createText(const std::string& text, + bool billboard = false, + float scaling = 1.0f, + const Color& c = Color::Black(), + float offsetX = 20.0f, + float offsetY = 20.0f, + float offsetZ = 0.0f); + + virtual VisualizationNodePtr createTorus(float radius, + float tubeRadius, + float completion = 1, + const Color& color = Color::Gray(), + int sides = 8, + int rings = 30); - virtual VisualizationNodePtr createCircleArrow(float /*radius*/, float /*tubeRadius*/, float /*completion*/ = 1, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f, float /*transparency*/ = 0.0f, int /*sides*/ = 8, int /*rings*/ = 30) - { - return nullptr; - } - - virtual VisualizationNodePtr createCylinder(float /*radius*/, float /*height*/, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createCoordSystem(float /*scaling*/ = 1.0f, std::string* /*text*/ = NULL, float /*axisLength*/ = 100.0f, float /*axisSize*/ = 3.0f, int /*nrOfBlocks*/ = 10) - { - return nullptr; - } - virtual VisualizationNodePtr createBoundingBox(const BoundingBox& /*bbox*/, bool /*wireFrame*/ = false) - { - return nullptr; - } - virtual VisualizationNodePtr createVertexVisualization(const Eigen::Vector3f& /*position*/, float /*radius*/, float /*transparency*/, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - - virtual VisualizationNodePtr createTriMeshModelVisualization(const TriMeshModelPtr& /*model*/, const Eigen::Matrix4f& /*pose*/, float /*scaleX*/ = 1.0f, float /*scaleY*/ = 1.0f, float /*scaleZ*/ = 1.0f) - { - return nullptr; - } - - virtual VisualizationNodePtr createTriMeshModelVisualization(const TriMeshModelPtr& /*model*/, bool /*showNormals*/, const Eigen::Matrix4f& /*pose*/, bool /*showLines*/ = true) - { - return nullptr; - } - virtual VisualizationNodePtr createPlane(const Eigen::Vector3f& /*position*/, const Eigen::Vector3f& /*normal*/, float /*extend*/, float /*transparency*/, float /*colorR*/ = 0.5f, float /*colorG*/ = 0.5f, float /*colorB*/ = 0.5f) - { - return nullptr; - } - virtual VisualizationNodePtr createPlane(const MathTools::Plane& plane, float extend, float transparency, float colorR = 0.5f, float colorG = 0.5f, float colorB = 0.5f) - { - return createPlane(plane.p, plane.n, extend, transparency, colorR, colorG, colorB); - } - virtual VisualizationNodePtr createArrow(const Eigen::Vector3f& /*n*/, float /*length*/ = 50.0f, float /*width*/ = 2.0f, const Color& /*color*/ = Color::Gray()) - { - return nullptr; - } - virtual VisualizationNodePtr createTrajectory(TrajectoryPtr /*t*/, Color /*colorNode*/ = Color::Blue(), Color /*colorLine*/ = Color::Gray(), float /*nodeSize*/ = 15.0f, float /*lineSize*/ = 4.0f) - { - return nullptr; - } - virtual VisualizationNodePtr createText(const std::string& /*text*/, bool /*billboard*/ = false, float /*scaling*/ = 1.0f, Color /*c*/ = Color::Black(), float /*offsetX*/ = 20.0f, float /*offsetY*/ = 20.0f, float /*offsetZ*/ = 0.0f) - { - return nullptr; - } /*! Creates an coordinate axis aligned ellipse \param x The extend in x direction must be >= 1e-6 @@ -234,4 +247,3 @@ namespace VirtualRobot typedef std::shared_ptr<VisualizationFactory::Color> ColorPtr; } // namespace VirtualRobot - diff --git a/VirtualRobot/examples/RobotViewer/DiffIKWidget.cpp b/VirtualRobot/examples/RobotViewer/DiffIKWidget.cpp index 2fa4a431698bbbb08fdefb544ab746875a8a4a34..de75728283fb4732818ca3c5c3ba863aae08264b 100644 --- a/VirtualRobot/examples/RobotViewer/DiffIKWidget.cpp +++ b/VirtualRobot/examples/RobotViewer/DiffIKWidget.cpp @@ -297,6 +297,8 @@ void DiffIKWidget::updateEndeffectorPoseVis(VirtualRobot::RobotNodeSetPtr robotN mat->transparency.setValue(0.5); sep->addChild(mat); + using Color = VirtualRobot::CoinVisualizationFactory::Color; + if (ui->checkBoxOriIK->isChecked()) { auto visNode = tcp->getVisualization(VirtualRobot::SceneObject::Full); auto coinVisNode = std::dynamic_pointer_cast<VirtualRobot::CoinVisualizationNode>(visNode); @@ -305,11 +307,11 @@ void DiffIKWidget::updateEndeffectorPoseVis(VirtualRobot::RobotNodeSetPtr robotN sep->addChild(coinVis); } else { - sep->addChild(VirtualRobot::CoinVisualizationFactory::CreateSphere(50, 1, 0, 0)); + sep->addChild(VirtualRobot::CoinVisualizationFactory::CreateSphere(50, Color::Red())); } } else { - sep->addChild(VirtualRobot::CoinVisualizationFactory::CreateSphere(50, 1, 0, 0)); + sep->addChild(VirtualRobot::CoinVisualizationFactory::CreateSphere(50, Color::Red())); } endeffectorSep->addChild(sep); } diff --git a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp index 2326f0b53e784773254c4d3fae3d16dda58bd9dc..8865b4f574b8e7d66d91bae3af321dccd4319cd5 100644 --- a/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp +++ b/VirtualRobot/examples/RobotViewer/showRobotWindow.cpp @@ -445,10 +445,11 @@ void showRobotWindow::updatePointDistanceVisu() const Eigen::Vector3f dir = (pt1 - pt2).normalized(); const float spherSize = 10; using Factory = VirtualRobot::CoinVisualizationFactory; + using Color = VirtualRobot::CoinVisualizationFactory::Color; ptDistance.sep->addChild(Factory::CreateArrow(pt2, dir, distance)); - ptDistance.sep->addChild(Factory::CreateSphere(pt, spherSize, 0, 1, 0)); - ptDistance.sep->addChild(Factory::CreateSphere(pt1, spherSize, 0, 0, 1)); - ptDistance.sep->addChild(Factory::CreateSphere(pt2, spherSize, 0, 1, 1)); + ptDistance.sep->addChild(Factory::CreateSphere(pt, spherSize, Color::Green())); + ptDistance.sep->addChild(Factory::CreateSphere(pt1, spherSize, Color::Blue())); + ptDistance.sep->addChild(Factory::CreateSphere(pt2, spherSize, Color(0,1,1))); } UI.labelDistancePtDist->setText(QString::number(distance));