Skip to content

Commit

Permalink
Merge pull request #651 from ignitionrobotics/particle_modification
Browse files Browse the repository at this point in the history
Support particle modification
  • Loading branch information
nkoenig authored Mar 1, 2021
1 parent 8e29cda commit 1a16084
Show file tree
Hide file tree
Showing 6 changed files with 88 additions and 56 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR})

#--------------------------------------
# Find ignition-msgs
ign_find_package(ignition-msgs6 REQUIRED VERSION 6.3)
ign_find_package(ignition-msgs6 REQUIRED VERSION 6.4)
set(IGN_MSGS_VER ${ignition-msgs6_VERSION_MAJOR})

#--------------------------------------
Expand Down
15 changes: 13 additions & 2 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -179,6 +179,9 @@ class ignition::gazebo::RenderUtilPrivate
public: std::unordered_map<Entity, msgs::ParticleEmitter>
newParticleEmittersCmds;

/// \brief A list of entities with particle emitter cmds to remove
public: std::vector<Entity> particleCmdsToRemove;

/// \brief Map of ids of entites to be removed and sim iteration when the
/// remove request is received
public: std::unordered_map<Entity, uint64_t> removeEntities;
Expand Down Expand Up @@ -342,14 +345,21 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/,
{
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);

// Remove the commands from the entity
// these are commands from the last iteration. We want to make sure all
// systems have a chance to process them first before they are removed.
for (const auto &entity : this->dataPtr->particleCmdsToRemove)
_ecm.RemoveComponent<components::ParticleEmitterCmd>(entity);
this->dataPtr->particleCmdsToRemove.clear();

// particle emitters commands
_ecm.Each<components::ParticleEmitterCmd>(
[&](const Entity &_entity,
const components::ParticleEmitterCmd *_emitterCmd) -> bool
{
// store emitter properties and update them in rendering thread
this->dataPtr->newParticleEmittersCmds[_entity] =
_emitterCmd->Data();
_emitterCmd->Data();

// update pose comp here
if (_emitterCmd->Data().has_pose())
Expand All @@ -358,7 +368,8 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/,
if (poseComp)
poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose());
}
_ecm.RemoveComponent<components::ParticleEmitterCmd>(_entity);
// Store the entity ids to clear outside of the `Each` loop.
this->dataPtr->particleCmdsToRemove.push_back(_entity);

return true;
});
Expand Down
36 changes: 25 additions & 11 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1059,7 +1059,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}
default:
{
emitter->SetType(ignition::rendering::EmitterType::EM_POINT);
// Do nothing if type is not set.
}
}

Expand All @@ -1068,20 +1068,28 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
emitter->SetEmitterSize(ignition::msgs::Convert(_emitter.size()));

// Rate.
emitter->SetRate(_emitter.rate());
if (_emitter.has_rate())
emitter->SetRate(_emitter.rate().data());

// Duration.
emitter->SetDuration(_emitter.duration());
if (_emitter.has_duration())
emitter->SetDuration(_emitter.duration().data());

// Emitting.
emitter->SetEmitting(_emitter.emitting());
if (_emitter.has_emitting()) {
emitter->SetEmitting(_emitter.emitting().data());
}

// Particle size.
emitter->SetParticleSize(
ignition::msgs::Convert(_emitter.particle_size()));
if (_emitter.has_particle_size())
{
emitter->SetParticleSize(
ignition::msgs::Convert(_emitter.particle_size()));
}

// Lifetime.
emitter->SetLifetime(_emitter.lifetime());
if (_emitter.has_lifetime())
emitter->SetLifetime(_emitter.lifetime().data());

// Material.
if (_emitter.has_material())
Expand All @@ -1092,12 +1100,17 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}

// Velocity range.
emitter->SetVelocityRange(_emitter.min_velocity(), _emitter.max_velocity());
if (_emitter.has_min_velocity() && _emitter.has_max_velocity())
{
emitter->SetVelocityRange(_emitter.min_velocity().data(),
_emitter.max_velocity().data());
}

// Color range image.
if (!_emitter.color_range_image().empty())
if (_emitter.has_color_range_image() &&
!_emitter.color_range_image().data().empty())
{
emitter->SetColorRangeImage(_emitter.color_range_image());
emitter->SetColorRangeImage(_emitter.color_range_image().data());
}
// Color range.
else if (_emitter.has_color_start() && _emitter.has_color_end())
Expand All @@ -1108,7 +1121,8 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}

// Scale rate.
emitter->SetScaleRate(_emitter.scale_rate());
if (_emitter.has_scale_rate())
emitter->SetScaleRate(_emitter.scale_rate().data());

// pose
if (_emitter.has_pose())
Expand Down
21 changes: 13 additions & 8 deletions src/systems/particle_emitter/ParticleEmitter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -188,13 +188,16 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_size(), size);

// Rate.
this->dataPtr->emitter.set_rate(_sdf->Get<double>("rate", 10).first);
this->dataPtr->emitter.mutable_rate()->set_data(
_sdf->Get<double>("rate", 10).first);

// Duration.
this->dataPtr->emitter.set_duration(_sdf->Get<double>("duration", 0).first);
this->dataPtr->emitter.mutable_duration()->set_data(
_sdf->Get<double>("duration", 0).first);

// Emitting.
this->dataPtr->emitter.set_emitting(_sdf->Get<bool>("emitting", false).first);
this->dataPtr->emitter.mutable_emitting()->set_data(
_sdf->Get<bool>("emitting", false).first);

// Particle size.
size = ignition::math::Vector3d::One;
Expand All @@ -203,7 +206,8 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_particle_size(), size);

// Lifetime.
this->dataPtr->emitter.set_lifetime(_sdf->Get<double>("lifetime", 5).first);
this->dataPtr->emitter.mutable_lifetime()->set_data(
_sdf->Get<double>("lifetime", 5).first);

// Material.
if (_sdf->HasElement("material"))
Expand All @@ -216,11 +220,11 @@ void ParticleEmitter::Configure(const Entity &_entity,
}

// Min velocity.
this->dataPtr->emitter.set_min_velocity(
this->dataPtr->emitter.mutable_min_velocity()->set_data(
_sdf->Get<double>("min_velocity", 1).first);

// Max velocity.
this->dataPtr->emitter.set_max_velocity(
this->dataPtr->emitter.mutable_max_velocity()->set_data(
_sdf->Get<double>("max_velocity", 1).first);

// Color start.
Expand All @@ -236,7 +240,7 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), color);

// Scale rate.
this->dataPtr->emitter.set_scale_rate(
this->dataPtr->emitter.mutable_scale_rate()->set_data(
_sdf->Get<double>("scale_rate", 1).first);

// Color range image.
Expand All @@ -250,7 +254,8 @@ void ParticleEmitter::Configure(const Entity &_entity,
systemPaths.SetFilePathEnv(kResourcePathEnv);
auto absolutePath = systemPaths.FindFile(path);

this->dataPtr->emitter.set_color_range_image(absolutePath);
this->dataPtr->emitter.mutable_color_range_image()->set_data(
absolutePath);
}

igndbg << "Loading particle emitter:" << std::endl
Expand Down
36 changes: 18 additions & 18 deletions test/integration/components.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1520,15 +1520,15 @@ TEST_F(ComponentsTest, ParticleEmitter)
emitter1.mutable_size()->set_x(1);
emitter1.mutable_size()->set_y(2);
emitter1.mutable_size()->set_z(3);
emitter1.set_rate(4.0);
emitter1.set_duration(5.0);
emitter1.set_emitting(false);
emitter1.mutable_rate()->set_data(4.0);
emitter1.mutable_duration()->set_data(5.0);
emitter1.mutable_emitting()->set_data(false);
emitter1.mutable_particle_size()->set_x(0.1);
emitter1.mutable_particle_size()->set_y(0.2);
emitter1.mutable_particle_size()->set_z(0.3);
emitter1.set_lifetime(6.0);
emitter1.set_min_velocity(7.0);
emitter1.set_max_velocity(8.0);
emitter1.mutable_lifetime()->set_data(6.0);
emitter1.mutable_min_velocity()->set_data(7.0);
emitter1.mutable_max_velocity()->set_data(8.0);
emitter1.mutable_color_start()->set_r(1.0);
emitter1.mutable_color_start()->set_g(0);
emitter1.mutable_color_start()->set_b(0);
Expand All @@ -1537,8 +1537,8 @@ TEST_F(ComponentsTest, ParticleEmitter)
emitter1.mutable_color_end()->set_g(1.0);
emitter1.mutable_color_end()->set_b(1.0);
emitter1.mutable_color_end()->set_a(0);
emitter1.set_scale_rate(9.0);
emitter1.set_color_range_image("path_to_texture");
emitter1.mutable_scale_rate()->set_data(9.0);
emitter1.mutable_color_range_image()->set_data("path_to_texture");

msgs::ParticleEmitter emitter2;
emitter2.set_name("emitter2");
Expand All @@ -1547,15 +1547,15 @@ TEST_F(ComponentsTest, ParticleEmitter)
emitter2.mutable_size()->set_x(1);
emitter2.mutable_size()->set_y(2);
emitter2.mutable_size()->set_z(3);
emitter2.set_rate(4.0);
emitter2.set_duration(5.0);
emitter2.set_emitting(false);
emitter2.mutable_rate()->set_data(4.0);
emitter2.mutable_duration()->set_data(5.0);
emitter2.mutable_emitting()->set_data(false);
emitter2.mutable_particle_size()->set_x(0.1);
emitter2.mutable_particle_size()->set_y(0.2);
emitter2.mutable_particle_size()->set_z(0.3);
emitter2.set_lifetime(6.0);
emitter2.set_min_velocity(7.0);
emitter2.set_max_velocity(8.0);
emitter2.mutable_lifetime()->set_data(6.0);
emitter2.mutable_min_velocity()->set_data(7.0);
emitter2.mutable_max_velocity()->set_data(8.0);
emitter2.mutable_color_start()->set_r(1.0);
emitter2.mutable_color_start()->set_g(0);
emitter2.mutable_color_start()->set_b(0);
Expand All @@ -1564,8 +1564,8 @@ TEST_F(ComponentsTest, ParticleEmitter)
emitter2.mutable_color_end()->set_g(1.0);
emitter2.mutable_color_end()->set_b(1.0);
emitter2.mutable_color_end()->set_a(0);
emitter2.set_scale_rate(9.0);
emitter2.set_color_range_image("path_to_texture");
emitter2.mutable_scale_rate()->set_data(9.0);
emitter2.mutable_color_range_image()->set_data("path_to_texture");

// Create components.
auto comp1 = components::ParticleEmitter(emitter1);
Expand All @@ -1586,7 +1586,7 @@ TEST_F(ComponentsTest, ParticleEmitterCmd)
{
msgs::ParticleEmitter emitter1;
emitter1.set_name("emitter1");
emitter1.set_emitting(true);
emitter1.mutable_emitting()->set_data(true);

// Create components.
auto comp1 = components::ParticleEmitterCmd(emitter1);
Expand All @@ -1598,6 +1598,6 @@ TEST_F(ComponentsTest, ParticleEmitterCmd)
std::istringstream istr(ostr.str());
components::ParticleEmitter comp3;
comp3.Deserialize(istr);
EXPECT_EQ(comp1.Data().emitting(), comp3.Data().emitting());
EXPECT_EQ(comp1.Data().emitting().data(), comp3.Data().emitting().data());
EXPECT_EQ(comp1.Data().name(), comp3.Data().name());
}
34 changes: 18 additions & 16 deletions test/integration/particle_emitter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -97,27 +97,29 @@ TEST_F(ParticleEmitterTest, SDFLoad)
msgs::Convert(_emitter->Data().pose()));
EXPECT_EQ(math::Vector3d(2, 2, 2),
msgs::Convert(_emitter->Data().size()));
EXPECT_DOUBLE_EQ(5.0, _emitter->Data().rate());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().duration());
EXPECT_TRUE(_emitter->Data().emitting());
EXPECT_DOUBLE_EQ(5.0, _emitter->Data().rate().data());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().duration().data());
EXPECT_TRUE(_emitter->Data().emitting().data());
EXPECT_EQ(math::Vector3d(3, 3, 3),
msgs::Convert(_emitter->Data().particle_size()));
EXPECT_DOUBLE_EQ(2.0, _emitter->Data().lifetime());
EXPECT_DOUBLE_EQ(2.0, _emitter->Data().lifetime().data());
// TODO(anyone) add material check here
EXPECT_DOUBLE_EQ(10.0, _emitter->Data().min_velocity());
EXPECT_DOUBLE_EQ(20.0, _emitter->Data().max_velocity());
EXPECT_DOUBLE_EQ(10.0,
_emitter->Data().min_velocity().data());
EXPECT_DOUBLE_EQ(20.0,
_emitter->Data().max_velocity().data());
EXPECT_EQ(math::Color::Blue,
msgs::Convert(_emitter->Data().color_start()));
EXPECT_EQ(math::Color::Green,
msgs::Convert(_emitter->Data().color_end()));
EXPECT_DOUBLE_EQ(10.0, _emitter->Data().scale_rate());
EXPECT_DOUBLE_EQ(10.0, _emitter->Data().scale_rate().data());

// color range image is empty because the emitter system
// will not be able to find a file that does not exist
// TODO(anyone) this should return "/path/to/dummy_image.png"
// and let rendering do the findFile instead
EXPECT_EQ(std::string(),
_emitter->Data().color_range_image());
_emitter->Data().color_range_image().data());
}
else
{
Expand All @@ -133,21 +135,21 @@ TEST_F(ParticleEmitterTest, SDFLoad)
msgs::Convert(_emitter->Data().pose()));
EXPECT_EQ(math::Vector3d(1, 1, 1),
msgs::Convert(_emitter->Data().size()));
EXPECT_DOUBLE_EQ(10.0, _emitter->Data().rate());
EXPECT_DOUBLE_EQ(0.0, _emitter->Data().duration());
EXPECT_FALSE(_emitter->Data().emitting());
EXPECT_DOUBLE_EQ(10.0, _emitter->Data().rate().data());
EXPECT_DOUBLE_EQ(0.0, _emitter->Data().duration().data());
EXPECT_FALSE(_emitter->Data().emitting().data());
EXPECT_EQ(math::Vector3d(1, 1, 1),
msgs::Convert(_emitter->Data().particle_size()));
EXPECT_DOUBLE_EQ(5.0, _emitter->Data().lifetime());
EXPECT_DOUBLE_EQ(5.0, _emitter->Data().lifetime().data());
// TODO(anyone) add material check here
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().min_velocity());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().max_velocity());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().min_velocity().data());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().max_velocity().data());
EXPECT_EQ(math::Color::White,
msgs::Convert(_emitter->Data().color_start()));
EXPECT_EQ(math::Color::White,
msgs::Convert(_emitter->Data().color_end()));
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().scale_rate());
EXPECT_EQ("", _emitter->Data().color_range_image());
EXPECT_DOUBLE_EQ(1.0, _emitter->Data().scale_rate().data());
EXPECT_EQ("", _emitter->Data().color_range_image().data());
}

return true;
Expand Down

0 comments on commit 1a16084

Please sign in to comment.