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

Particle emitter based on SDF #730

Merged
merged 10 commits into from
Apr 9, 2021
Merged
Show file tree
Hide file tree
Changes from 3 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
5 changes: 5 additions & 0 deletions examples/worlds/particle_emitter.sdf
Original file line number Diff line number Diff line change
@@ -1,5 +1,10 @@
<?xml version="1.0" ?>

<!-- NOTE: This world uses a particle emitter that is implemented as
a plugin. We recommend using particle emitters based on the SDF
specification. See the test/worlds/particle_emitter2.sdf example.
-->

<!--
Launch this example with:

Expand Down
92 changes: 92 additions & 0 deletions examples/worlds/particle_emitter2.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,92 @@
<?xml version="1.0" ?>

<!--
Launch this example with:

ign gazebo -r particle_emitter.sdf

Try modifying some parameters of the emitter:

To disable the particle emitter:

ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: false}'

Enable back the particle emitter:

ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'emitting: {data: true}'

Then, change the particle rate:

ign topic -t /model/fog_generator/link/fog_link/particle_emitter/emitter/cmd -m ignition.msgs.ParticleEmitter -p 'rate: {data: 100}'
-->

<sdf version="1.6">
<world name="particle_emitters">

<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>
<plugin
filename="ignition-gazebo-particle-emitter2-system"
name="ignition::gazebo::systems::ParticleEmitter2">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<include>
<uri>https://fuel.ignitionrobotics.org/1.0/openrobotics/models/fog generator</uri>
</include>

</world>
</sdf>
38 changes: 38 additions & 0 deletions include/ignition/gazebo/Conversions.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <ignition/msgs/inertial.pb.h>
#include <ignition/msgs/light.pb.h>
#include <ignition/msgs/material.pb.h>
#include <ignition/msgs/particle_emitter.pb.h>
#include <ignition/msgs/physics.pb.h>
#include <ignition/msgs/scene.pb.h>
#include <ignition/msgs/sensor.pb.h>
Expand All @@ -47,6 +48,7 @@
#include <sdf/Light.hh>
#include <sdf/Material.hh>
#include <sdf/Noise.hh>
#include <sdf/ParticleEmitter.hh>
#include <sdf/Physics.hh>
#include <sdf/Scene.hh>
#include <sdf/Sensor.hh>
Expand Down Expand Up @@ -624,6 +626,42 @@ namespace ignition
/// \return Axis aligned box object.
template<>
math::AxisAlignedBox convert(const msgs::AxisAlignedBox &_in);

/// \brief Generic conversion from a particle emitter SDF object to another
/// type.
/// \param[in] _in Particle emitter SDF object.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const sdf::ParticleEmitter &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from a particle emitter SDF object to
/// a particle emitter message object.
/// \param[in] _in Particle emitter SDF object.
/// \return Particle emitter message.
template<>
msgs::ParticleEmitter convert(const sdf::ParticleEmitter &_in);

/// \brief Generic conversion from a particle emitter SDF object to another
/// type.
/// \param[in] _in Particle emitter SDF object.
/// \return Conversion result.
/// \tparam Out Output type.
template<class Out>
Out convert(const msgs::ParticleEmitter &/*_in*/)
{
Out::ConversionNotImplemented;
}

/// \brief Specialized conversion from a particle emitter SDF object to
/// a particle emitter message object.
/// \param[in] _in Particle emitter SDF object.
/// \return Particle emitter message.
template<>
sdf::ParticleEmitter convert(const msgs::ParticleEmitter &_in);
}
}
}
Expand Down
8 changes: 8 additions & 0 deletions include/ignition/gazebo/SdfEntityCreator.hh
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include <sdf/Light.hh>
#include <sdf/Link.hh>
#include <sdf/Model.hh>
#include <sdf/ParticleEmitter.hh>
#include <sdf/Physics.hh>
#include <sdf/Sensor.hh>
#include <sdf/Visual.hh>
Expand Down Expand Up @@ -140,6 +141,13 @@ namespace ignition
/// \sa CreateEntities(const sdf::Model *)
public: Entity CreateEntities(const sdf::Sensor *_sensor);

/// \brief Create all entities that exist in the
/// sdf::ParticleEmitter object.
/// \param[in] _emitter SDF ParticleEmitter object.
/// \return ParticleEmitter entity.
/// \sa CreateEntities(const sdf::Link *)
public: Entity CreateEntities(const sdf::ParticleEmitter *_emitter);

/// \brief Request an entity deletion. This will insert the request
/// into a queue. The queue is processed toward the end of a simulation
/// update step.
Expand Down
127 changes: 127 additions & 0 deletions src/Conversions.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1326,3 +1326,130 @@ math::AxisAlignedBox ignition::gazebo::convert(const msgs::AxisAlignedBox &_in)
out.Max() = msgs::Convert(_in.max_corner());
return out;
}

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
msgs::ParticleEmitter ignition::gazebo::convert(const sdf::ParticleEmitter &_in)
{
msgs::ParticleEmitter out;
out.set_name(_in.Name());
switch(_in.Type())
{
default:
case sdf::ParticleEmitterType::POINT:
out.set_type(msgs::ParticleEmitter::POINT);
break;
case sdf::ParticleEmitterType::BOX:
out.set_type(msgs::ParticleEmitter::BOX);
break;
case sdf::ParticleEmitterType::CYLINDER:
out.set_type(msgs::ParticleEmitter::CYLINDER);
break;
case sdf::ParticleEmitterType::ELLIPSOID:
out.set_type(msgs::ParticleEmitter::ELLIPSOID);
break;
}

msgs::Set(out.mutable_pose(), _in.RawPose());
msgs::Set(out.mutable_size(), _in.Size());
msgs::Set(out.mutable_particle_size(), _in.ParticleSize());
out.mutable_rate()->set_data(_in.Rate());
out.mutable_duration()->set_data(_in.Duration());
out.mutable_emitting()->set_data(_in.Emitting());
out.mutable_lifetime()->set_data(_in.Lifetime());
if (_in.Material())
{
out.mutable_material()->CopyFrom(convert<msgs::Material>(*_in.Material()));
}
out.mutable_min_velocity()->set_data(_in.MinVelocity());
out.mutable_max_velocity()->set_data(_in.MaxVelocity());
msgs::Set(out.mutable_color_start(), _in.ColorStart());
msgs::Set(out.mutable_color_end(), _in.ColorEnd());
out.mutable_scale_rate()->set_data(_in.ScaleRate());
out.mutable_color_range_image()->set_data(_in.ColorRangeImage());

if (!_in.ColorRangeImage().empty())
nkoenig marked this conversation as resolved.
Show resolved Hide resolved
{
std::string path = asFullPath(_in.ColorRangeImage(), _in.FilePath());

common::SystemPaths systemPaths;
systemPaths.SetFilePathEnv(kResourcePathEnv);
std::string absolutePath = systemPaths.FindFile(path);

if (!absolutePath.empty())
out.mutable_color_range_image()->set_data(absolutePath);
}

/// \todo(nkoenig) Modify the particle_emitter.proto file to
/// have a topic field.
if (!_in.Topic().empty())
{
auto header = out.mutable_header()->add_data();
header->set_key("topic");
header->add_value(_in.Topic());
}

return out;
}

//////////////////////////////////////////////////
template<>
IGNITION_GAZEBO_VISIBLE
sdf::ParticleEmitter ignition::gazebo::convert(const msgs::ParticleEmitter &_in)
{
sdf::ParticleEmitter out;
out.SetName(_in.name());
switch(_in.type())
{
default:
case msgs::ParticleEmitter::POINT:
out.SetType(sdf::ParticleEmitterType::POINT);
break;
case msgs::ParticleEmitter::BOX:
out.SetType(sdf::ParticleEmitterType::BOX);
break;
case msgs::ParticleEmitter::CYLINDER:
out.SetType(sdf::ParticleEmitterType::CYLINDER);
break;
case msgs::ParticleEmitter::ELLIPSOID:
out.SetType(sdf::ParticleEmitterType::ELLIPSOID);
break;
}
out.SetRawPose(msgs::Convert(_in.pose()));
out.SetSize(msgs::Convert(_in.size()));
out.SetParticleSize(msgs::Convert(_in.particle_size()));
out.SetMinVelocity(msgs::Convert(_in.min_velocity()));
out.SetMaxVelocity(msgs::Convert(_in.max_velocity()));
out.SetColorStart(msgs::Convert(_in.color_start()));
out.SetColorEnd(msgs::Convert(_in.color_end()));

if (_in.has_material())
{
out.SetMaterial(convert<sdf::Material>(_in.material()));
}

if (_in.has_rate())
out.SetRate(_in.rate().data());
if (_in.has_duration())
out.SetDuration(_in.duration().data());
if (_in.has_emitting())
out.SetEmitting(_in.emitting().data());
if (_in.has_lifetime())
out.SetLifetime(_in.lifetime().data());
if (_in.has_scale_rate())
out.SetScaleRate(_in.scale_rate().data());
if (_in.has_color_range_image())
out.SetColorRangeImage(_in.color_range_image().data());

for (int i = 0; i < _in.header().data_size(); ++i)
{
auto data = _in.header().data(i);
if (data.key() == "topic" && data.value_size() > 0)
{
out.SetTopic(data.value(0));
}
}

return out;
}
80 changes: 80 additions & 0 deletions src/Conversions_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -773,3 +773,83 @@ TEST(Conversions, Actor)
EXPECT_EQ(math::Pose3d(6, 5, 4, 0, 0, 0),
newActor.TrajectoryByIndex(0)->WaypointByIndex(0)->Pose());
}

/////////////////////////////////////////////////
TEST(Conversions, ParticleEmitter)
{
sdf::ParticleEmitter emitter;
emitter.SetName("my_emitter");
emitter.SetType(sdf::ParticleEmitterType::BOX);
emitter.SetEmitting(false);
emitter.SetDuration(12);
emitter.SetLifetime(56);
emitter.SetRate(0.5);
emitter.SetScaleRate(1.2);
emitter.SetMinVelocity(0.1);
emitter.SetMaxVelocity(0.2);
emitter.SetSize(math::Vector3d(1, 2, 3));
emitter.SetParticleSize(math::Vector3d(4, 5, 6));
emitter.SetColorStart(math::Color(0.1, 0.2, 0.3));
emitter.SetColorEnd(math::Color(0.4, 0.5, 0.6));
emitter.SetColorRangeImage("range_image");
emitter.SetTopic("my_topic");
emitter.SetRawPose(math::Pose3d(1, 2, 3, 0, 0, 0));

sdf::Material material;
sdf::Pbr pbr;
sdf::PbrWorkflow workflow;
workflow.SetType(sdf::PbrWorkflowType::METAL);
workflow.SetAlbedoMap("albedo_map.png");
pbr.SetWorkflow(workflow.Type(), workflow);
material.SetPbrMaterial(pbr);

emitter.SetMaterial(material);

// Convert SDF to a message.
msgs::ParticleEmitter emitterMsg = convert<msgs::ParticleEmitter>(emitter);

EXPECT_EQ("my_emitter", emitterMsg.name());
EXPECT_EQ(msgs::ParticleEmitter::BOX, emitterMsg.type());
EXPECT_FALSE(emitterMsg.emitting().data());
EXPECT_NEAR(12, emitterMsg.duration().data(), 1e-3);
EXPECT_NEAR(56, emitterMsg.lifetime().data(), 1e-3);
EXPECT_NEAR(0.5, emitterMsg.rate().data(), 1e-3);
EXPECT_NEAR(1.2, emitterMsg.scale_rate().data(), 1e-3);
EXPECT_NEAR(0.1, emitterMsg.min_velocity().data(), 1e-3);
EXPECT_NEAR(0.2, emitterMsg.max_velocity().data(), 1e-3);
EXPECT_EQ(math::Vector3d(1, 2, 3), msgs::Convert(emitterMsg.size()));
EXPECT_EQ(math::Vector3d(4, 5, 6), msgs::Convert(emitterMsg.particle_size()));
EXPECT_EQ(math::Color(0.1, 0.2, 0.3),
msgs::Convert(emitterMsg.color_start()));
EXPECT_EQ(math::Color(0.4, 0.5, 0.6), msgs::Convert(emitterMsg.color_end()));
EXPECT_EQ("range_image", emitterMsg.color_range_image().data());

auto header = emitterMsg.header().data(0);
EXPECT_EQ("topic", header.key());
EXPECT_EQ("my_topic", header.value(0));

EXPECT_EQ(math::Pose3d(1, 2, 3, 0, 0, 0), msgs::Convert(emitterMsg.pose()));

auto pbrMsg = emitterMsg.material().pbr();
EXPECT_EQ(msgs::Material::PBR::METAL, pbrMsg.type());
EXPECT_EQ("albedo_map.png", pbrMsg.albedo_map());

// Convert the message back to SDF.
sdf::ParticleEmitter emitter2 = convert<sdf::ParticleEmitter>(emitterMsg);
EXPECT_EQ(emitter2.Name(), emitter.Name());
EXPECT_EQ(emitter2.Type(), emitter.Type());
EXPECT_EQ(emitter2.Emitting(), emitter.Emitting());
EXPECT_NEAR(emitter2.Duration(), emitter.Duration(), 1e-3);
EXPECT_NEAR(emitter2.Lifetime(), emitter.Lifetime(), 1e-3);
EXPECT_NEAR(emitter2.Rate(), emitter.Rate(), 1e-3);
EXPECT_NEAR(emitter2.ScaleRate(), emitter.ScaleRate(), 1e-3);
EXPECT_NEAR(emitter2.MinVelocity(), emitter.MinVelocity(), 1e-3);
EXPECT_NEAR(emitter2.MaxVelocity(), emitter.MaxVelocity(), 1e-3);
EXPECT_EQ(emitter2.Size(), emitter.Size());
EXPECT_EQ(emitter2.ParticleSize(), emitter.ParticleSize());
EXPECT_EQ(emitter2.ColorStart(), emitter.ColorStart());
EXPECT_EQ(emitter2.ColorEnd(), emitter.ColorEnd());
EXPECT_EQ(emitter2.ColorRangeImage(), emitter.ColorRangeImage());
EXPECT_EQ(emitter2.Topic(), emitter.Topic());
EXPECT_EQ(emitter2.RawPose(), emitter.RawPose());
}
Loading