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

Commit

Permalink
Added shininess to models (#3213)
Browse files Browse the repository at this point in the history
* Advertise shininess to renderer

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Updated comments

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Added codee suggestions

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Added codee suggestions

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Require sdformat9 9.8

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>

* Added code suggestions

Signed-off-by: William Lew <WilliamMilesLew@gmail.com>
  • Loading branch information
WilliamLewww authored May 6, 2022
1 parent 2f0f7af commit f6d2b94
Show file tree
Hide file tree
Showing 8 changed files with 176 additions and 1 deletion.
2 changes: 1 addition & 1 deletion cmake/gazebo-config.cmake.in
Original file line number Diff line number Diff line change
Expand Up @@ -171,7 +171,7 @@ list(APPEND @PKG_NAME@_INCLUDE_DIRS ${PROTOBUF_INCLUDE_DIRS})
list(APPEND @PKG_NAME@_LIBRARIES ${PROTOBUF_LIBRARIES})

# Find SDFormat
find_package(sdformat9 REQUIRED)
find_package(sdformat9 REQUIRED VERSION 9.8)
list(APPEND @PKG_NAME@_INCLUDE_DIRS ${SDFormat_INCLUDE_DIRS})
list(APPEND @PKG_NAME@_LIBRARIES ${SDFormat_LIBRARIES})

Expand Down
35 changes: 35 additions & 0 deletions gazebo/physics/World.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1259,6 +1259,32 @@ ModelPtr World::LoadModel(sdf::ElementPtr _sdf , BasePtr _parent)
}
}

sdf::ElementPtr linkElem = _sdf->GetElement("link");
if (linkElem->HasElement("visual") &&
linkElem->GetElement("visual")->HasElement("material"))
{
sdf::ElementPtr matElem = linkElem->GetElement("visual")->
GetElement("material");

if (matElem->HasElement("shininess"))
{
this->dataPtr->materialShininessMap[modelName] =
matElem->Get<double>("shininess");
}
else
{
this->dataPtr->materialShininessMap[modelName] = 0;
}

std::string materialShininessService("/" + modelName + "/shininess");
if (!this->dataPtr->ignNode.Advertise(materialShininessService,
&World::MaterialShininessService, this))
{
gzerr << "Error advertising service ["
<< materialShininessService << "]" << std::endl;
}
}

model = this->dataPtr->physicsEngine->CreateModel(_parent);
model->SetWorld(shared_from_this());
model->Load(_sdf);
Expand Down Expand Up @@ -3437,3 +3463,12 @@ bool World::ShadowCasterRenderBackFacesService(ignition::msgs::Boolean &_res)
_res.set_data(this->dataPtr->shadowCasterRenderBackFaces);
return true;
}

//////////////////////////////////////////////////
bool World::MaterialShininessService(
const ignition::msgs::StringMsg &_req, msgs::Any &_res)
{
_res.set_type(msgs::Any::DOUBLE);
_res.set_double_value(this->dataPtr->materialShininessMap[_req.data()]);
return true;
}
7 changes: 7 additions & 0 deletions gazebo/physics/World.hh
Original file line number Diff line number Diff line change
Expand Up @@ -671,6 +671,13 @@ namespace gazebo
private: bool ShadowCasterRenderBackFacesService(
ignition::msgs::Boolean &_response);

/// \brief Callback for "<model_name>/shininess" service.
/// \param[in] _request Message containing the model name.
/// \param[out] _response Message containing shininess value.
/// \return True if the info was successfully obtained.
private: bool MaterialShininessService(
const ignition::msgs::StringMsg &_request, msgs::Any &_response);

/// \internal
/// \brief Private data pointer.
private: std::unique_ptr<WorldPrivate> dataPtr;
Expand Down
3 changes: 3 additions & 0 deletions gazebo/physics/WorldPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -397,6 +397,9 @@ namespace gazebo

/// \brief Shadow caster render back faces from scene SDF
public: bool shadowCasterRenderBackFaces = true;

/// \brief Shininess values from scene SDF
public: std::map<std::string, double> materialShininessMap;
};
}
}
Expand Down
43 changes: 43 additions & 0 deletions gazebo/rendering/Visual.cc
Original file line number Diff line number Diff line change
Expand Up @@ -346,6 +346,48 @@ void Visual::Load(sdf::ElementPtr _sdf)
//////////////////////////////////////////////////
void Visual::Load()
{
if (this->dataPtr->sdf->HasElement("material"))
{
// Get shininess value from physics::World
ignition::transport::Node node;
msgs::Any rep;

const std::string visualName =
this->Name().substr(0, this->Name().find(":"));

const std::string serviceName = "/" + visualName + "/shininess";

const std::string validServiceName =
ignition::transport::TopicUtils::AsValidTopic(serviceName);

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

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::endl;
}
else
{
gzerr << "Service call [" << validServiceName << "] timed out"
<< std::endl;
}
}

std::ostringstream stream;
ignition::math::Pose3d pose;
Ogre::MovableObject *obj = nullptr;
Expand Down Expand Up @@ -1432,6 +1474,7 @@ void Visual::SetSpecular(const ignition::math::Color &_color,
{
pass = technique->getPass(passCount);
pass->setSpecular(Conversions::Convert(_color));
pass->setShininess(this->dataPtr->shininess);
}
}
}
Expand Down
2 changes: 2 additions & 0 deletions gazebo/rendering/Visual.hh
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,8 @@
#include <ignition/math/Quaternion.hh>
#include <ignition/math/Vector3.hh>
#include <ignition/msgs/MessageTypes.hh>
#include <ignition/transport/Node.hh>
#include <ignition/transport/TopicUtils.hh>

#include "gazebo/common/Mesh.hh"
#include "gazebo/common/Time.hh"
Expand Down
3 changes: 3 additions & 0 deletions gazebo/rendering/VisualPrivate.hh
Original file line number Diff line number Diff line change
Expand Up @@ -186,6 +186,9 @@ namespace gazebo
public: ignition::math::Color specular =
ignition::math::Color(0, 0, 0, 0);

/// \brief Specular exponent of the visual.
public: double shininess = 0;

/// \brief Emissive color of the visual.
public: ignition::math::Color emissive =
ignition::math::Color(0, 0, 0, 0);
Expand Down
82 changes: 82 additions & 0 deletions worlds/shapes_shininess.world
Original file line number Diff line number Diff line change
@@ -0,0 +1,82 @@
<?xml version="1.0" ?>
<sdf version="1.5">
<world name="default">
<include>
<uri>model://ground_plane</uri>
</include>
<include>
<uri>model://sun</uri>
</include>
<model name="box">
<pose>0 0 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
<visual name="visual">
<material>
<specular>1 0 0 1</specular>
<shininess>1</shininess>
</material>
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</visual>
</link>
</model>
<model name="sphere">
<pose>0 1.5 0.5 0 0 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</collision>
<visual name="visual">
<material>
<specular>0 1 0 1</specular>
<shininess>5</shininess>
</material>
<geometry>
<sphere>
<radius>0.5</radius>
</sphere>
</geometry>
</visual>
</link>
</model>
<model name="cylinder">
<pose>0 -1.5 0.5 0 1.5707 0</pose>
<link name="link">
<collision name="collision">
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
</collision>
<visual name="visual">
<material>
<specular>0 0 1 1</specular>
<shininess>10</shininess>
</material>
<geometry>
<cylinder>
<radius>0.5</radius>
<length>1.0</length>
</cylinder>
</geometry>
</visual>
</link>
</model>
</world>
</sdf>

0 comments on commit f6d2b94

Please sign in to comment.