Skip to content
This repository has been archived by the owner on Feb 3, 2025. It is now read-only.

Fix shininess and add tests #3231

Merged
merged 5 commits into from
Jun 29, 2022
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
96 changes: 59 additions & 37 deletions gazebo/rendering/Visual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -327,6 +327,27 @@ void Visual::Init()
this->dataPtr->inheritTransparency = true;
this->dataPtr->scale = ignition::math::Vector3d::One;

this->dataPtr->initialized = true;
}

//////////////////////////////////////////////////
void Visual::LoadFromMsg(const boost::shared_ptr<msgs::Visual const> &_msg)
{
this->dataPtr->sdf = msgs::VisualToSDF(*_msg.get());
this->Load();
this->UpdateFromMsg(_msg);
}

//////////////////////////////////////////////////
void Visual::Load(sdf::ElementPtr _sdf)
{
this->dataPtr->sdf->Copy(_sdf);
this->Load();
}

//////////////////////////////////////////////////
void Visual::Load()
{
if (this->dataPtr->sdf->HasElement("material"))
{
// Get shininess value from physics::World
Expand All @@ -341,55 +362,50 @@ void Visual::Init()
const std::string validServiceName =
ignition::transport::TopicUtils::AsValidTopic(serviceName);

bool tryServiceCall = true;
if (validServiceName.empty())
{
gzerr << "Service name [" << serviceName << "] not valid" << std::endl;
return;
tryServiceCall = false;
}

ignition::msgs::StringMsg req;
req.set_data(visualName);

bool result;
unsigned int timeout = 5000;
bool executed = node.Request(validServiceName, req, timeout, rep, result);

if (executed)
{
if (result)
this->dataPtr->shininess = rep.double_value();
else
gzerr << "Service call [" << validServiceName << "] failed"
std::vector<ignition::transport::ServicePublisher> publishers;
if (!node.ServiceInfo(validServiceName, publishers))
{
gzerr << "Service name [" << validServiceName << "] not advertised, "
<< "not attempting to load shininess for visual with name ["
<< this->Name() << "]."
<< std::endl;
tryServiceCall = false;
}
}
else
{
gzerr << "Service call [" << validServiceName << "] timed out"
<< std::endl;
}
}

this->dataPtr->initialized = true;
}
if (tryServiceCall)
{
ignition::msgs::StringMsg req;
req.set_data(visualName);

//////////////////////////////////////////////////
void Visual::LoadFromMsg(const boost::shared_ptr< msgs::Visual const> &_msg)
{
this->dataPtr->sdf = msgs::VisualToSDF(*_msg.get());
this->Load();
this->UpdateFromMsg(_msg);
}
bool result;
unsigned int timeout = 5000;
bool executed = node.Request(validServiceName, req, timeout, rep, result);

//////////////////////////////////////////////////
void Visual::Load(sdf::ElementPtr _sdf)
{
this->dataPtr->sdf->Copy(_sdf);
this->Load();
}
if (executed)
{
if (result)
this->dataPtr->shininess = rep.double_value();
else
gzerr << "Service call [" << validServiceName << "] failed"
<< std::endl;
}
else
{
gzerr << "Service call [" << validServiceName << "] timed out"
<< std::endl;
}
}
}

//////////////////////////////////////////////////
void Visual::Load()
{
std::ostringstream stream;
ignition::math::Pose3d pose;
Ogre::MovableObject *obj = nullptr;
Expand Down Expand Up @@ -1575,6 +1591,12 @@ ignition::math::Color Visual::Emissive() const
return this->dataPtr->emissive;
}

/////////////////////////////////////////////////
double Visual::Shininess() const
{
return this->dataPtr->shininess;
}

//////////////////////////////////////////////////
void Visual::SetWireframe(bool _show)
{
Expand Down
4 changes: 4 additions & 0 deletions gazebo/rendering/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -272,6 +272,10 @@ namespace gazebo
/// \return Emissive color.
public: ignition::math::Color Emissive() const;

/// \brief Get the shininess value of the visual.
/// \return Floating-point shininess value.
public: double Shininess() const;

/// \brief Enable or disable wireframe for this visual.
/// \param[in] _show True to enable wireframe for this visual.
public: void SetWireframe(bool _show);
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/Visual_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -951,6 +951,7 @@ TEST_F(Visual_TEST, Color)
EXPECT_EQ(cylinderVis->Diffuse(), ignmath::Color::Black);
EXPECT_EQ(cylinderVis->Specular(), ignmath::Color::Black);
EXPECT_EQ(cylinderVis->Emissive(), ignmath::Color::Black);
EXPECT_DOUBLE_EQ(0.0, cylinderVis->Shininess());

sdf::ElementPtr cylinderSDF2(new sdf::Element);
sdf::initFile("visual.sdf", cylinderSDF2);
Expand All @@ -965,6 +966,7 @@ TEST_F(Visual_TEST, Color)
EXPECT_EQ(cylinderVis2->Diffuse(), ignmath::Color::Blue);
EXPECT_EQ(cylinderVis2->Specular(), ignmath::Color::Red);
EXPECT_EQ(cylinderVis2->Emissive(), ignmath::Color::Yellow);
EXPECT_DOUBLE_EQ(0.0, cylinderVis2->Shininess());

// test changing ambient/diffuse/specular colors
{
Expand Down
1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -205,6 +205,7 @@ set(dri_tests
road.cc
speed_pr2.cc
visual.cc
visual_shininess.cc
wideanglecamera_sensor.cc
world_remove.cc
world_reset.cc
Expand Down
116 changes: 116 additions & 0 deletions test/integration/visual_shininess.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,116 @@
/*
* Copyright (C) 2022 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*
*/

#include "test_config.h"

#include "gazebo/common/Timer.hh"
#include "gazebo/rendering/rendering.hh"

#include "gazebo/test/ServerFixture.hh"

using namespace gazebo;
class VisualShininess : public RenderingFixture
{
};

/////////////////////////////////////////////////
void CheckShininessService(const std::string &_modelName,
double _expectedShininess)
{
std::string serviceName = '/' + _modelName + "/shininess";
ignition::transport::Node ignNode;

{
std::vector<ignition::transport::ServicePublisher> publishers;
EXPECT_TRUE(ignNode.ServiceInfo(serviceName, publishers));
}

ignition::msgs::StringMsg request;
gazebo::msgs::Any reply;
const unsigned int timeout = 3000;
bool result = false;
request.set_data(_modelName);
EXPECT_TRUE(ignNode.Request(serviceName, request, timeout, reply, result));
EXPECT_TRUE(result);
EXPECT_EQ(msgs::Any_ValueType_DOUBLE, reply.type());
EXPECT_DOUBLE_EQ(_expectedShininess, reply.double_value()) << _modelName;
}

/////////////////////////////////////////////////
TEST_F(VisualShininess, ShapesShininessServices)
{
Load("worlds/shapes_shininess.world", true);

CheckShininessService("ground_plane", 0.0);
CheckShininessService("box", 1.0);
CheckShininessService("sphere", 5.0);
CheckShininessService("cylinder", 10.0);
}

/////////////////////////////////////////////////
TEST_F(VisualShininess, ShapesShininess)
{
Load("worlds/shapes_shininess.world");

// Make sure the render engine is available.
if (rendering::RenderEngine::Instance()->GetRenderPathType() ==
rendering::RenderEngine::NONE)
{
gzerr << "No rendering engine, unable to run shininess test"
<< std::endl;
return;
}
gazebo::rendering::ScenePtr scene = gazebo::rendering::get_scene();
ASSERT_NE(nullptr, scene);

// Wait until all models are inserted
unsigned int sleep = 0;
unsigned int maxSleep = 30;
rendering::VisualPtr box, sphere, cylinder;
while ((!box || !sphere || !cylinder) && sleep < maxSleep)
{
event::Events::preRender();
event::Events::render();
event::Events::postRender();

box = scene->GetVisual("box");
cylinder = scene->GetVisual("cylinder");
sphere = scene->GetVisual("sphere");

common::Time::MSleep(100);
sleep++;
}
ASSERT_NE(nullptr, box);
ASSERT_NE(nullptr, cylinder);
ASSERT_NE(nullptr, sphere);
EXPECT_TRUE(scene->Initialized());

std::unordered_map<std::string, double> nameToShininess;
nameToShininess["box::link::visual"] = 1.0;
nameToShininess["sphere::link::visual"] = 5.0;
nameToShininess["cylinder::link::visual"] = 10.0;

for (const auto &nameShininess : nameToShininess)
{
rendering::VisualPtr visual = scene->GetVisual(nameShininess.first);
ASSERT_NE(nullptr, visual);

// check shininess value
EXPECT_DOUBLE_EQ(nameShininess.second, visual->Shininess())
<< nameShininess.first;
}
}