diff --git a/examples/worlds/particle_emitter.sdf b/examples/worlds/particle_emitter.sdf new file mode 100644 index 00000000000..58fb36c3bed --- /dev/null +++ b/examples/worlds/particle_emitter.sdf @@ -0,0 +1,90 @@ + + + + + + + + + 0.001 + 1.0 + + + + + + + + + + true + 0 0 10 0 0 0 + 1 1 1 1 + 0.5 0.5 0.5 1 + + 1000 + 0.9 + 0.01 + 0.001 + + -0.5 0.1 -0.9 + + + + true + + + + + 0 0 1 + + + + + + + 0 0 1 + 100 100 + + + + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + 0.8 0.8 0.8 1 + + + + + + + https://fuel.ignitionrobotics.org/1.0/caguero/models/smoke_generator + + + + + + diff --git a/include/ignition/gazebo/components/ParticleEmitter.hh b/include/ignition/gazebo/components/ParticleEmitter.hh index a6ec2a242ce..86fc36bd883 100644 --- a/include/ignition/gazebo/components/ParticleEmitter.hh +++ b/include/ignition/gazebo/components/ParticleEmitter.hh @@ -37,6 +37,13 @@ namespace components serializers::MsgSerializer>; IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter", ParticleEmitter) + + /// \brief A component that contains a particle emitter command. + using ParticleEmitterCmd = Component; + IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd", + ParticleEmitterCmd) } } } diff --git a/include/ignition/gazebo/rendering/SceneManager.hh b/include/ignition/gazebo/rendering/SceneManager.hh index 113c8731a85..f7643e250f1 100644 --- a/include/ignition/gazebo/rendering/SceneManager.hh +++ b/include/ignition/gazebo/rendering/SceneManager.hh @@ -34,6 +34,8 @@ #include #include +#include + #include #include @@ -161,6 +163,21 @@ inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { public: rendering::LightPtr CreateLight(Entity _id, const sdf::Light &_light, Entity _parentId); + /// \brief Create a particle emitter. + /// \param[in] _id Unique particle emitter id + /// \param[in] _emitter Particle emitter data + /// \param[in] _parentId Parent id + /// \return Default particle emitter object created + public: rendering::ParticleEmitterPtr CreateParticleEmitter( + Entity _id, const msgs::ParticleEmitter &_emitter, Entity _parentId); + + /// \brief Update an existing particle emitter + /// \brief _id Emitter id to update + /// \brief _emitter Data to update the particle emitter + /// \return Particle emitter updated + public: rendering::ParticleEmitterPtr UpdateParticleEmitter(Entity _id, + const msgs::ParticleEmitter &_emitter); + /// \brief Ignition sensors is the one responsible for adding sensors /// to the scene. Here we just keep track of it and make sure it has /// the correct parent. diff --git a/src/gui/plugins/scene3d/Scene3D.cc b/src/gui/plugins/scene3d/Scene3D.cc index b22da15d99c..e43b7498938 100644 --- a/src/gui/plugins/scene3d/Scene3D.cc +++ b/src/gui/plugins/scene3d/Scene3D.cc @@ -2752,6 +2752,7 @@ void Scene3D::Update(const UpdateInfo &_info, msgs::Pose poseMsg = msgs::Convert(renderWindow->CameraPose()); this->dataPtr->cameraPosePub.Publish(poseMsg); } + this->dataPtr->renderUtil->UpdateECM(_info, _ecm); this->dataPtr->renderUtil->UpdateFromECM(_info, _ecm); // check if video recording is enabled and if we need to lock step diff --git a/src/rendering/RenderUtil.cc b/src/rendering/RenderUtil.cc index c1c507713b5..d1f833d12d4 100644 --- a/src/rendering/RenderUtil.cc +++ b/src/rendering/RenderUtil.cc @@ -42,6 +42,8 @@ #include #include +#include + #include #include #include @@ -60,6 +62,7 @@ #include "ignition/gazebo/components/Model.hh" #include "ignition/gazebo/components/Name.hh" #include "ignition/gazebo/components/ParentEntity.hh" +#include "ignition/gazebo/components/ParticleEmitter.hh" #include "ignition/gazebo/components/Pose.hh" #include "ignition/gazebo/components/RgbdCamera.hh" #include "ignition/gazebo/components/Scene.hh" @@ -163,6 +166,17 @@ class ignition::gazebo::RenderUtilPrivate public: std::vector> newSensors; + /// \brief New particle emitter to be created. The elements in the tuple are: + /// [0] entity id, [1], particle emitter, [2] parent entity id + public: std::vector> + newParticleEmitters; + + /// \brief New particle emitter commands to be requested. + /// The map key and value are: entity id of the particle emitter to + /// update, and particle emitter msg + public: std::unordered_map + newParticleEmittersCmds; + /// \brief Map of ids of entites to be removed and sim iteration when the /// remove request is received public: std::unordered_map removeEntities; @@ -289,6 +303,28 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/, EntityComponentManager &_ecm) { std::lock_guard lock(this->dataPtr->updateMutex); + + // particle emitters commands + _ecm.Each( + [&](const Entity &_entity, + const components::ParticleEmitterCmd *_emitterCmd) -> bool + { + // store emitter properties and update them in rendering thread + this->dataPtr->newParticleEmittersCmds[_entity] = + _emitterCmd->Data(); + + // update pose comp here + if (_emitterCmd->Data().has_pose()) + { + auto poseComp = _ecm.Component(_entity); + if (poseComp) + poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose()); + } + _ecm.RemoveComponent(_entity); + + return true; + }); + // Update thermal cameras _ecm.Each( [&](const Entity &_entity, @@ -413,6 +449,9 @@ void RenderUtil::Update() auto newVisuals = std::move(this->dataPtr->newVisuals); auto newActors = std::move(this->dataPtr->newActors); auto newLights = std::move(this->dataPtr->newLights); + auto newParticleEmitters = std::move(this->dataPtr->newParticleEmitters); + auto newParticleEmittersCmds = + std::move(this->dataPtr->newParticleEmittersCmds); auto removeEntities = std::move(this->dataPtr->removeEntities); auto entityPoses = std::move(this->dataPtr->entityPoses); auto trajectoryPoses = std::move(this->dataPtr->trajectoryPoses); @@ -428,6 +467,8 @@ void RenderUtil::Update() this->dataPtr->newVisuals.clear(); this->dataPtr->newActors.clear(); this->dataPtr->newLights.clear(); + this->dataPtr->newParticleEmitters.clear(); + this->dataPtr->newParticleEmittersCmds.clear(); this->dataPtr->removeEntities.clear(); this->dataPtr->entityPoses.clear(); this->dataPtr->trajectoryPoses.clear(); @@ -529,6 +570,18 @@ void RenderUtil::Update() std::get<0>(light), std::get<1>(light), std::get<2>(light)); } + for (const auto &emitter : newParticleEmitters) + { + this->dataPtr->sceneManager.CreateParticleEmitter( + std::get<0>(emitter), std::get<1>(emitter), std::get<2>(emitter)); + } + + for (const auto &emitterCmd : newParticleEmittersCmds) + { + this->dataPtr->sceneManager.UpdateParticleEmitter( + emitterCmd.first, emitterCmd.second); + } + if (this->dataPtr->enableSensors && this->dataPtr->createSensorCb) { for (const auto &sensor : newSensors) @@ -1013,6 +1066,17 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // particle emitters + _ecm.Each( + [&](const Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::ParentEntity *_parent) -> bool + { + this->newParticleEmitters.push_back( + std::make_tuple(_entity, _emitter->Data(), _parent->Data())); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -1224,6 +1288,17 @@ void RenderUtilPrivate::CreateRenderingEntities( return true; }); + // particle emitters + _ecm.EachNew( + [&](const Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::ParentEntity *_parent) -> bool + { + this->newParticleEmitters.push_back( + std::make_tuple(_entity, _emitter->Data(), _parent->Data())); + return true; + }); + if (this->enableSensors) { // Create cameras @@ -1465,6 +1540,14 @@ void RenderUtilPrivate::RemoveRenderingEntities( return true; }); + // particle emitters + _ecm.EachRemoved( + [&](const Entity &_entity, const components::ParticleEmitter *)->bool + { + this->removeEntities[_entity] = _info.iterations; + return true; + }); + // cameras _ecm.EachRemoved( [&](const Entity &_entity, const components::Camera *)->bool diff --git a/src/rendering/SceneManager.cc b/src/rendering/SceneManager.cc index 9bdfe0b1bbc..c4e603d4303 100644 --- a/src/rendering/SceneManager.cc +++ b/src/rendering/SceneManager.cc @@ -29,16 +29,20 @@ #include #include #include +#include #include #include -#include + +#include #include #include #include +#include #include #include +#include "ignition/gazebo/Conversions.hh" #include "ignition/gazebo/Util.hh" #include "ignition/gazebo/rendering/SceneManager.hh" @@ -75,6 +79,10 @@ class ignition::gazebo::SceneManagerPrivate /// \brief Map of light entity in Gazebo to light pointers. public: std::map lights; + /// \brief Map of particle emitter entity in Gazebo to particle emitter + /// rendering pointers. + public: std::map particleEmitters; + /// \brief Map of sensor entity in Gazebo to sensor pointers. public: std::map sensors; @@ -960,6 +968,148 @@ rendering::LightPtr SceneManager::CreateLight(Entity _id, return light; } +///////////////////////////////////////////////// +rendering::ParticleEmitterPtr SceneManager::CreateParticleEmitter( + Entity _id, const msgs::ParticleEmitter &_emitter, Entity _parentId) +{ + if (!this->dataPtr->scene) + return rendering::ParticleEmitterPtr(); + + if (this->dataPtr->particleEmitters.find(_id) != + this->dataPtr->particleEmitters.end()) + { + ignerr << "Particle emitter with Id: [" << _id << "] already exists in the " + <<" scene" << std::endl; + return rendering::ParticleEmitterPtr(); + } + + rendering::VisualPtr parent; + if (_parentId != this->dataPtr->worldId) + { + auto it = this->dataPtr->visuals.find(_parentId); + if (it == this->dataPtr->visuals.end()) + { + // It is possible to get here if the model entity is created then + // removed in between render updates. + return rendering::ParticleEmitterPtr(); + } + parent = it->second; + } + + // Name. + std::string name = _emitter.name().empty() ? std::to_string(_id) : + _emitter.name(); + if (parent) + name = parent->Name() + "::" + name; + + rendering::ParticleEmitterPtr emitter; + emitter = this->dataPtr->scene->CreateParticleEmitter(name); + + this->dataPtr->particleEmitters[_id] = emitter; + + if (parent) + parent->AddChild(emitter); + + this->UpdateParticleEmitter(_id, _emitter); + + return emitter; +} + +///////////////////////////////////////////////// +rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id, + const msgs::ParticleEmitter &_emitter) +{ + if (!this->dataPtr->scene) + return rendering::ParticleEmitterPtr(); + + // Sanity check: Make sure that the id exists. + auto emitterIt = this->dataPtr->particleEmitters.find(_id); + if (emitterIt == this->dataPtr->particleEmitters.end()) + { + ignerr << "Particle emitter with Id: [" << _id << "] not found in the " + << "scene" << std::endl; + return rendering::ParticleEmitterPtr(); + } + auto emitter = emitterIt->second; + + // Type. + switch (_emitter.type()) + { + case ignition::msgs::ParticleEmitter_EmitterType_BOX: + { + emitter->SetType(ignition::rendering::EmitterType::EM_BOX); + break; + } + case ignition::msgs::ParticleEmitter_EmitterType_CYLINDER: + { + emitter->SetType(ignition::rendering::EmitterType::EM_CYLINDER); + break; + } + case ignition::msgs::ParticleEmitter_EmitterType_ELLIPSOID: + { + emitter->SetType(ignition::rendering::EmitterType::EM_ELLIPSOID); + break; + } + default: + { + emitter->SetType(ignition::rendering::EmitterType::EM_POINT); + } + } + + // Emitter size. + if (_emitter.has_size()) + emitter->SetEmitterSize(ignition::msgs::Convert(_emitter.size())); + + // Rate. + emitter->SetRate(_emitter.rate()); + + // Duration. + emitter->SetDuration(_emitter.duration()); + + // Emitting. + emitter->SetEmitting(_emitter.emitting()); + + // Particle size. + emitter->SetParticleSize( + ignition::msgs::Convert(_emitter.particle_size())); + + // Lifetime. + emitter->SetLifetime(_emitter.lifetime()); + + // Material. + if (_emitter.has_material()) + { + ignition::rendering::MaterialPtr material = + this->LoadMaterial(convert(_emitter.material())); + emitter->SetMaterial(material); + } + + // Velocity range. + emitter->SetVelocityRange(_emitter.min_velocity(), _emitter.max_velocity()); + + // Color range image. + if (!_emitter.color_range_image().empty()) + { + emitter->SetColorRangeImage(_emitter.color_range_image()); + } + // Color range. + else if (_emitter.has_color_start() && _emitter.has_color_end()) + { + emitter->SetColorRange( + ignition::msgs::Convert(_emitter.color_start()), + ignition::msgs::Convert(_emitter.color_end())); + } + + // Scale rate. + emitter->SetScaleRate(_emitter.scale_rate()); + + // pose + if (_emitter.has_pose()) + emitter->SetLocalPose(msgs::Convert(_emitter.pose())); + + return emitter; +} + ///////////////////////////////////////////////// bool SceneManager::AddSensor(Entity _gazeboId, const std::string &_sensorName, Entity _parentGazeboId) @@ -1010,6 +1160,8 @@ bool SceneManager::HasEntity(Entity _id) const return this->dataPtr->visuals.find(_id) != this->dataPtr->visuals.end() || this->dataPtr->actors.find(_id) != this->dataPtr->actors.end() || this->dataPtr->lights.find(_id) != this->dataPtr->lights.end() || + this->dataPtr->particleEmitters.find(_id) != + this->dataPtr->particleEmitters.end() || this->dataPtr->sensors.find(_id) != this->dataPtr->sensors.end(); } @@ -1021,22 +1173,22 @@ rendering::NodePtr SceneManager::NodeById(Entity _id) const { return vIt->second; } - else + auto lIt = this->dataPtr->lights.find(_id); + if (lIt != this->dataPtr->lights.end()) { - auto lIt = this->dataPtr->lights.find(_id); - if (lIt != this->dataPtr->lights.end()) - { - return lIt->second; - } - else - { - auto sIt = this->dataPtr->sensors.find(_id); - if (sIt != this->dataPtr->sensors.end()) - { - return sIt->second; - } - } + return lIt->second; } + auto sIt = this->dataPtr->sensors.find(_id); + if (sIt != this->dataPtr->sensors.end()) + { + return sIt->second; + } + auto pIt = this->dataPtr->particleEmitters.find(_id); + if (pIt != this->dataPtr->particleEmitters.end()) + { + return pIt->second; + } + return rendering::NodePtr(); } @@ -1258,6 +1410,16 @@ void SceneManager::RemoveEntity(Entity _id) } } + { + auto it = this->dataPtr->particleEmitters.find(_id); + if (it != this->dataPtr->particleEmitters.end()) + { + this->dataPtr->scene->DestroyVisual(it->second); + this->dataPtr->particleEmitters.erase(it); + return; + } + } + { auto it = this->dataPtr->sensors.find(_id); if (it != this->dataPtr->sensors.end()) diff --git a/src/systems/particle_emitter/CMakeLists.txt b/src/systems/particle_emitter/CMakeLists.txt index 297e9a418fd..9e75a90abf9 100644 --- a/src/systems/particle_emitter/CMakeLists.txt +++ b/src/systems/particle_emitter/CMakeLists.txt @@ -2,5 +2,8 @@ gz_add_system(particle-emitter SOURCES ParticleEmitter.cc PUBLIC_LINK_LIBS + ignition-common${IGN_COMMON_VER}::ignition-common${IGN_COMMON_VER} ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER} + ignition-plugin${IGN_PLUGIN_VER}::ignition-plugin${IGN_PLUGIN_VER} + ignition-transport${IGN_TRANSPORT_VER}::ignition-transport${IGN_TRANSPORT_VER} ) diff --git a/src/systems/particle_emitter/ParticleEmitter.cc b/src/systems/particle_emitter/ParticleEmitter.cc index 8f3b1fd9296..072bd50dd2d 100644 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -17,6 +17,7 @@ #include +#include #include #include @@ -24,11 +25,16 @@ #include #include #include +#include #include #include #include +#include #include +#include +#include +#include #include #include "ParticleEmitter.hh" @@ -39,18 +45,36 @@ using namespace systems; // Private data class. class ignition::gazebo::systems::ParticleEmitterPrivate { - /// \brief The particle emitter. + /// \brief Callback for receiving particle emitter commands. + /// \param[in] _msg Particle emitter message. + public: void OnCmd(const ignition::msgs::ParticleEmitter &_msg); + + /// \brief The particle emitter parsed from SDF. public: ignition::msgs::ParticleEmitter emitter; - /// \brief Get a RGBA color representation based on a color's - /// string representation. - /// \param[in] _colorStr The string representation of a color (ex: "black"), - /// which is case sensitive (the string representation should be lowercase). - /// \return The Color, represented in RGBA format. If _colorStr is invalid, - /// ignition::math::Color::White is returned - public: ignition::math::Color GetColor(const std::string &_colorStr) const; + /// \brief The transport node. + public: ignition::transport::Node node; + + /// \brief Particle emitter entity. + public: Entity emitterEntity{kNullEntity}; + + /// \brief The particle emitter command requested externally. + public: ignition::msgs::ParticleEmitter userCmd; + + public: bool newDataReceived = false; + + /// \brief A mutex to protect the user command. + public: std::mutex mutex; }; +////////////////////////////////////////////////// +void ParticleEmitterPrivate::OnCmd(const msgs::ParticleEmitter &_msg) +{ + std::lock_guard lock(this->mutex); + this->userCmd = _msg; + this->newDataReceived = true; +} + ////////////////////////////////////////////////// ParticleEmitter::ParticleEmitter() : System(), dataPtr(std::make_unique()) @@ -58,14 +82,23 @@ ParticleEmitter::ParticleEmitter() } ////////////////////////////////////////////////// -void ParticleEmitter::Configure(const Entity &/*_entity*/, +void ParticleEmitter::Configure(const Entity &_entity, const std::shared_ptr &_sdf, EntityComponentManager &_ecm, - EventManager &/*_eventMgr*/) + EventManager &_eventMgr) { + Model model = Model(_entity); + + if (!model.Valid(_ecm)) + { + ignerr << "ParticleEmitter plugin should be attached to a model entity. " + << "Failed to initialize." << std::endl; + return; + } + // Create a particle emitter entity. - auto entity = _ecm.CreateEntity(); - if (entity == kNullEntity) + this->dataPtr->emitterEntity = _ecm.CreateEntity(); + if (this->dataPtr->emitterEntity == kNullEntity) { ignerr << "Failed to create a particle emitter entity" << std::endl; return; @@ -77,7 +110,8 @@ void ParticleEmitter::Configure(const Entity &/*_entity*/, allowRenaming = _sdf->Get("allow_renaming"); // Name. - std::string name = "particle_emitter_entity_" + std::to_string(entity); + std::string name = "particle_emitter_entity_" + + std::to_string(this->dataPtr->emitterEntity); if (_sdf->HasElement("emitter_name")) { std::set emitterNames; @@ -177,6 +211,7 @@ void ParticleEmitter::Configure(const Entity &/*_entity*/, sdf::Material material; material.Load(materialElem); ignition::msgs::Material materialMsg = convert(material); + this->dataPtr->emitter.mutable_material()->CopyFrom(materialMsg); } // Min velocity. @@ -188,71 +223,107 @@ void ParticleEmitter::Configure(const Entity &/*_entity*/, _sdf->Get("max_velocity", 1).first); // Color start. - ignition::msgs::Set(this->dataPtr->emitter.mutable_color_start(), - this->dataPtr->GetColor(_sdf->Get("color_start"))); + ignition::math::Color color = ignition::math::Color::White; + if (_sdf->HasElement("color_start")) + color = _sdf->Get("color_start"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_color_start(), color); // Color end. - ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), - this->dataPtr->GetColor(_sdf->Get("color_end"))); + color = ignition::math::Color::White; + if (_sdf->HasElement("color_end")) + color = _sdf->Get("color_end"); + ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), color); // Scale rate. this->dataPtr->emitter.set_scale_rate( _sdf->Get("scale_rate", 1).first); // Color range image. - this->dataPtr->emitter.set_color_range_image( - _sdf->Get("color_range_image", "").first); + if (_sdf->HasElement("color_range_image")) + { + auto modelPath = _ecm.ComponentData(_entity); + auto colorRangeImagePath = _sdf->Get("color_range_image"); + auto path = asFullPath(colorRangeImagePath, modelPath.value()); + + common::SystemPaths systemPaths; + systemPaths.SetFilePathEnv(kResourcePathEnv); + auto absolutePath = systemPaths.FindFile(path); + + this->dataPtr->emitter.set_color_range_image(absolutePath); + } igndbg << "Loading particle emitter:" << std::endl << this->dataPtr->emitter.DebugString() << std::endl; // Create components. - _ecm.CreateComponent(entity, components::Name(this->dataPtr->emitter.name())); + SdfEntityCreator sdfEntityCreator(_ecm, _eventMgr); + sdfEntityCreator.SetParent(this->dataPtr->emitterEntity, _entity); + + _ecm.CreateComponent(this->dataPtr->emitterEntity, + components::Name(this->dataPtr->emitter.name())); - _ecm.CreateComponent(entity, + _ecm.CreateComponent(this->dataPtr->emitterEntity, components::ParticleEmitter(this->dataPtr->emitter)); - _ecm.CreateComponent(entity, components::Pose(pose)); + _ecm.CreateComponent(this->dataPtr->emitterEntity, components::Pose(pose)); - igndbg << "Particle emitter has been loaded." << std::endl; + // Advertise the topic to receive particle emitter commands. + const std::string kDefaultTopic = + "/model/" + model.Name(_ecm) + "/particle_emitter/" + name; + std::string topic = _sdf->Get("topic", kDefaultTopic).first; + if (!this->dataPtr->node.Subscribe( + topic, &ParticleEmitterPrivate::OnCmd, this->dataPtr.get())) + { + ignerr << "Error subscribing to topic [" << topic << "]. " + << "Particle emitter will not receive updates." << std::endl; + return; + } + igndbg << "Subscribed to " << topic << " for receiving particle emitter " + << "updates" << std::endl; } ////////////////////////////////////////////////// -void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &/*_info*/, - ignition::gazebo::EntityComponentManager &/*_ecm*/) +void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) { IGN_PROFILE("ParticleEmitter::PreUpdate"); -} -////////////////////////////////////////////////// -ignition::math::Color ParticleEmitterPrivate::GetColor( - const std::string &_colorStr) const -{ - if (_colorStr == "black") - return ignition::math::Color::Black; - if (_colorStr == "red") - return ignition::math::Color::Red; - if (_colorStr == "green") - return ignition::math::Color::Green; - if (_colorStr == "blue") - return ignition::math::Color::Blue; - if (_colorStr == "yellow") - return ignition::math::Color::Yellow; - if (_colorStr == "magenta") - return ignition::math::Color::Magenta; - if (_colorStr == "cyan") - return ignition::math::Color::Cyan; - - // let users know an invalid string was given - // (_colorStr.empty() means that an empty string was parsed from SDF, - // which probably means that users never specified a color and are - // relying on the defaults) - if (!_colorStr.empty() && (_colorStr != "white")) + std::lock_guard lock(this->dataPtr->mutex); + + if (!this->dataPtr->newDataReceived) + return; + + // Nothing left to do if paused. + if (_info.paused) + return; + + this->dataPtr->newDataReceived = false; + + // Create component. + auto emitterComp = _ecm.Component( + this->dataPtr->emitterEntity); + if (!emitterComp) + { + _ecm.CreateComponent( + this->dataPtr->emitterEntity, + components::ParticleEmitterCmd(this->dataPtr->userCmd)); + } + else { - ignwarn << "Invalid color given (" << _colorStr - << "). Defaulting to white." << std::endl; + emitterComp->Data() = this->dataPtr->userCmd; + + // Note: we process the cmd component in RenderUtil but if there is only + // rendering on the gui side, it will not be able to remove the cmd + // component from the ECM. It seems like adding OneTimeChange here will make + // sure the cmd component is found again in Each call on GUI side. + // todo(anyone) find a better way to process this cmd component in + // RenderUtil.cc + _ecm.SetChanged(this->dataPtr->emitterEntity, + components::ParticleEmitterCmd::typeId, + ComponentState::OneTimeChange); } - return ignition::math::Color::White; + + igndbg << "New ParticleEmitterCmd component created" << std::endl; } IGNITION_ADD_PLUGIN(ParticleEmitter, diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh index 669863ce546..5b3df5e476e 100644 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -76,25 +76,20 @@ namespace systems /// ``: Sets the starting color for all particle emitted. /// The actual color will be interpolated between this color /// and the one set under . - /// Input is specified as a string (should be lower-case), - /// which could be one of the following: - /// * black - /// * red - /// * green - /// * blue - /// * yellow - /// * magenta - /// * cyan - /// * white - /// Default color is white. + /// Color::White is the default color for the particles + /// unless a specific function is used. + /// To specify a color, RGB values should be passed in. + /// For example, to specify red, a user should enter: + /// 1 0 0 /// Note that this function overrides the particle colors set /// with . /// ``: Sets the end color for all particle emitted. /// The actual color will be interpolated between this color /// and the one set under . - /// The input for follows the same rules as input - /// for . - /// Default color is white. + /// Color::White is the default color for the particles + /// unless a specific function is used (see color_start for + /// more information about defining custom colors with RGB + /// values). /// Note that this function overrides the particle colors set /// with . /// ``: Sets the amount by which to scale the particles in both x @@ -109,6 +104,12 @@ namespace systems /// image is used. /// Note that this function overrides the particle /// colors set with and . + /// ``: Topic used to update particle emitter properties at runtime. + /// The default topic is + /// /model//particle_emitter/ + /// Note that the emitter id and name may not be changed. + /// See the examples/worlds/particle_emitter.sdf example world for + /// example usage. class IGNITION_GAZEBO_VISIBLE ParticleEmitter : public System, public ISystemConfigure, diff --git a/test/integration/components.cc b/test/integration/components.cc index c48b60ddef0..28b10533290 100644 --- a/test/integration/components.cc +++ b/test/integration/components.cc @@ -1580,3 +1580,24 @@ TEST_F(ComponentsTest, ParticleEmitter) comp3.Deserialize(istr); EXPECT_EQ(comp1.Data().id(), comp3.Data().id()); } + +////////////////////////////////////////////////// +TEST_F(ComponentsTest, ParticleEmitterCmd) +{ + msgs::ParticleEmitter emitter1; + emitter1.set_name("emitter1"); + emitter1.set_emitting(true); + + // Create components. + auto comp1 = components::ParticleEmitterCmd(emitter1); + + // Stream operators. + std::ostringstream ostr; + comp1.Serialize(ostr); + + std::istringstream istr(ostr.str()); + components::ParticleEmitter comp3; + comp3.Deserialize(istr); + EXPECT_EQ(comp1.Data().emitting(), comp3.Data().emitting()); + EXPECT_EQ(comp1.Data().name(), comp3.Data().name()); +} diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index bafaf809838..9092438091a 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -112,7 +112,12 @@ TEST_F(ParticleEmitterTest, SDFLoad) EXPECT_EQ(math::Color::Green, msgs::Convert(_emitter->Data().color_end())); EXPECT_DOUBLE_EQ(10.0, _emitter->Data().scale_rate()); - EXPECT_EQ("/path/to/dummy_image.png", + + // 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()); } else diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index efbb4a49e96..1da40a4919b 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -117,9 +117,8 @@ 10 20 - - blue - green + 0 0 1 + 0 1 0 10 /path/to/dummy_image.png