Skip to content
New issue

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

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

Already on GitHub? Sign in to your account

Use URDF material color when specified #1295

Merged
merged 5 commits into from
Apr 29, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,10 @@

#### Changes

* Parser

* Changed URDF parser to use URDF material color when specified: [#1295](https://github.com/dartsim/dart/pull/1295)

* GUI

* Improved voxel grid and point cloud rendering performance: [#1294](https://github.com/dartsim/dart/pull/1294)
Expand Down
13 changes: 10 additions & 3 deletions dart/utils/urdf/DartLoader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -529,6 +529,7 @@ bool DartLoader::createDartNodeProperties(
return true;
}

//==============================================================================
void setMaterial(
const urdf::ModelInterface* model,
dynamics::VisualAspect* visualAspect,
Expand All @@ -542,10 +543,16 @@ void setMaterial(
if(m_it != model->materials_.end())
urdf_color = m_it->second->color;

Eigen::Vector4d color(urdf_color.r, urdf_color.g,
urdf_color.b, urdf_color.a);

const Eigen::Vector4d color(
static_cast<double>(urdf_color.r),
static_cast<double>(urdf_color.g),
static_cast<double>(urdf_color.b),
static_cast<double>(urdf_color.a));
visualAspect->setColor(color);
auto shapeFrame = visualAspect->getComposite();
auto shape = shapeFrame->getShape();
if (auto mesh = std::dynamic_pointer_cast<dynamics::MeshShape>(shape))
mesh->setColorMode(dynamics::MeshShape::ColorMode::SHAPE_COLOR);
}
}

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -293,20 +293,6 @@ int main()
loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf");
world->addSkeleton(robot);

// Set the colors of the models to obey the shape's color specification
for(std::size_t i=0; i<robot->getNumBodyNodes(); ++i)
{
BodyNode* bn = robot->getBodyNode(i);
auto shapeNodes = bn->getShapeNodesWith<dart::dynamics::VisualAspect>();
for(auto shapeNode : shapeNodes)
{
std::shared_ptr<MeshShape> mesh =
std::dynamic_pointer_cast<MeshShape>(shapeNode->getShape());
if(mesh)
mesh->setColorMode(MeshShape::SHAPE_COLOR);
}
}

// Rotate the robot so that z is upwards (default transform is not Identity)
robot->getJoint(0)->setTransformFromParentBodyNode(Eigen::Isometry3d::Identity());

Expand Down
14 changes: 0 additions & 14 deletions examples/osgExamples/osgPointCloud/main.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -432,20 +432,6 @@ dynamics::SkeletonPtr createRobot(const std::string& name)
auto robot
= urdfParser.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf");

// Set the colors of the models to obey the shape's color specification
for (std::size_t i = 0; i < robot->getNumBodyNodes(); ++i)
{
BodyNode* bn = robot->getBodyNode(i);
auto shapeNodes = bn->getShapeNodesWith<dart::dynamics::VisualAspect>();
for (auto shapeNode : shapeNodes)
{
std::shared_ptr<MeshShape> mesh
= std::dynamic_pointer_cast<MeshShape>(shapeNode->getShape());
if (mesh)
mesh->setColorMode(MeshShape::SHAPE_COLOR);
}
}

// Rotate the robot so that z is upwards (default transform is not Identity)
robot->getJoint(0)->setTransformFromParentBodyNode(
Eigen::Isometry3d::Identity());
Expand Down
27 changes: 27 additions & 0 deletions unittests/unit/test_DartLoader.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,8 +33,10 @@
#include <iostream>
#include <gtest/gtest.h>
#include "dart/dynamics/FreeJoint.hpp"
#include "dart/dynamics/MeshShape.hpp"
#include "dart/utils/urdf/DartLoader.hpp"

using namespace dart;
using dart::common::Uri;
using dart::utils::DartLoader;

Expand Down Expand Up @@ -407,3 +409,28 @@ TEST(DartLoader, MultiTreeRobot)
EXPECT_EQ(robot->getNumBodyNodes(), 2u);
EXPECT_EQ(robot->getNumTrees(), 2u);
}

//==============================================================================
TEST(DartLoader, KR5MeshColor)
{
DartLoader loader;
auto robot =
loader.parseSkeleton("dart://sample/urdf/KR5/KR5 sixx R650.urdf");
EXPECT_TRUE(nullptr != robot);

EXPECT_EQ(robot->getNumBodyNodes(), 7u);
EXPECT_EQ(robot->getNumTrees(), 1u);

for (auto i = 0u; i < robot->getNumBodyNodes(); ++i)
{
auto body = robot->getBodyNode(i);
for (auto shapeNode : body->getShapeNodesWith<dynamics::VisualAspect>())
{
auto shape = shapeNode->getShape();
if (auto mesh = std::dynamic_pointer_cast<dynamics::MeshShape>(shape))
{
EXPECT_EQ(mesh->getColorMode(), dynamics::MeshShape::SHAPE_COLOR);
}
}
}
}