From 038b59a70b2cb602a4ae276a9de990e5a421977e Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:03:39 -0800 Subject: [PATCH 1/8] Removed particle_emitter Signed-off-by: Nate Koenig --- src/systems/particle_emitter/CMakeLists.txt | 9 - .../particle_emitter/ParticleEmitter.cc | 352 ------------------ .../particle_emitter/ParticleEmitter.hh | 144 ------- 3 files changed, 505 deletions(-) delete mode 100644 src/systems/particle_emitter/CMakeLists.txt delete mode 100644 src/systems/particle_emitter/ParticleEmitter.cc delete mode 100644 src/systems/particle_emitter/ParticleEmitter.hh diff --git a/src/systems/particle_emitter/CMakeLists.txt b/src/systems/particle_emitter/CMakeLists.txt deleted file mode 100644 index 9e75a90abf9..00000000000 --- a/src/systems/particle_emitter/CMakeLists.txt +++ /dev/null @@ -1,9 +0,0 @@ -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 deleted file mode 100644 index db1aa6b924d..00000000000 --- a/src/systems/particle_emitter/ParticleEmitter.cc +++ /dev/null @@ -1,352 +0,0 @@ -/* - * Copyright (C) 2021 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 - -#include -#include -#include - -#include -#include -#include -#include -#include -#include - -#include -#include -#include -#include -#include -#include -#include -#include -#include -#include "ParticleEmitter.hh" - -using namespace ignition; -using namespace gazebo; -using namespace systems; - -// Private data class. -class ignition::gazebo::systems::ParticleEmitterPrivate -{ - /// \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 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()) -{ -} - -////////////////////////////////////////////////// -void ParticleEmitter::Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - 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. - this->dataPtr->emitterEntity = _ecm.CreateEntity(); - if (this->dataPtr->emitterEntity == kNullEntity) - { - ignerr << "Failed to create a particle emitter entity" << std::endl; - return; - } - - // allow_renaming - bool allowRenaming = false; - if (_sdf->HasElement("allow_renaming")) - allowRenaming = _sdf->Get("allow_renaming"); - - // Name. - std::string name = "particle_emitter_entity_" + - std::to_string(this->dataPtr->emitterEntity); - if (_sdf->HasElement("emitter_name")) - { - std::set emitterNames; - std::string emitterName = _sdf->Get("emitter_name"); - - // check to see if name is already taken - _ecm.Each( - [&emitterNames](const Entity &, const components::Name *_name, - const components::ParticleEmitter *) - { - emitterNames.insert(_name->Data()); - return true; - }); - - name = emitterName; - - // rename emitter if needed - if (emitterNames.find(emitterName) != emitterNames.end()) - { - if (!allowRenaming) - { - ignwarn << "Entity named [" << name - << "] already exists and " - << "[allow_renaming] is false. Entity not spawned." - << std::endl; - return; - } - int counter = 0; - while (emitterNames.find(name) != emitterNames.end()) - { - name = emitterName + "_" + std::to_string(++counter); - } - ignmsg << "Entity named [" << emitterName - << "] already exists. Renaming it to " << name << std::endl; - } - } - this->dataPtr->emitter.set_name(name); - - // Type. The default type is point. - this->dataPtr->emitter.set_type( - ignition::msgs::ParticleEmitter_EmitterType_POINT); - std::string type = _sdf->Get("type", "point").first; - if (type == "box") - { - this->dataPtr->emitter.set_type( - ignition::msgs::ParticleEmitter_EmitterType_BOX); - } - else if (type == "cylinder") - { - this->dataPtr->emitter.set_type( - ignition::msgs::ParticleEmitter_EmitterType_CYLINDER); - } - else if (type == "ellipsoid") - { - this->dataPtr->emitter.set_type( - ignition::msgs::ParticleEmitter_EmitterType_ELLIPSOID); - } - else if (type != "point") - { - ignerr << "Unknown emitter type [" << type << "]. Using [point] instead" - << std::endl; - } - - // Pose. - ignition::math::Pose3d pose = - _sdf->Get("pose"); - ignition::msgs::Set(this->dataPtr->emitter.mutable_pose(), pose); - - // Size. - ignition::math::Vector3d size = ignition::math::Vector3d::One; - if (_sdf->HasElement("size")) - size = _sdf->Get("size"); - ignition::msgs::Set(this->dataPtr->emitter.mutable_size(), size); - - // Rate. - this->dataPtr->emitter.mutable_rate()->set_data( - _sdf->Get("rate", 10).first); - - // Duration. - this->dataPtr->emitter.mutable_duration()->set_data( - _sdf->Get("duration", 0).first); - - // Emitting. - this->dataPtr->emitter.mutable_emitting()->set_data( - _sdf->Get("emitting", false).first); - - // Particle size. - size = ignition::math::Vector3d::One; - if (_sdf->HasElement("particle_size")) - size = _sdf->Get("particle_size"); - ignition::msgs::Set(this->dataPtr->emitter.mutable_particle_size(), size); - - // Lifetime. - this->dataPtr->emitter.mutable_lifetime()->set_data( - _sdf->Get("lifetime", 5).first); - - // Material. - if (_sdf->HasElement("material")) - { - auto materialElem = _sdf->GetElementImpl("material"); - sdf::Material material; - material.Load(materialElem); - ignition::msgs::Material materialMsg = convert(material); - this->dataPtr->emitter.mutable_material()->CopyFrom(materialMsg); - } - - // Min velocity. - this->dataPtr->emitter.mutable_min_velocity()->set_data( - _sdf->Get("min_velocity", 1).first); - - // Max velocity. - this->dataPtr->emitter.mutable_max_velocity()->set_data( - _sdf->Get("max_velocity", 1).first); - - // 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. - 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.mutable_scale_rate()->set_data( - _sdf->Get("scale_rate", 1).first); - - // Color range image. - 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.mutable_color_range_image()->set_data( - absolutePath); - } - - // particle scatter ratio - const std::string scatterRatioKey = "particle_scatter_ratio"; - if (_sdf->HasElement(scatterRatioKey)) - { - // todo(anyone) add particle_scatter_ratio field in next release of ign-msgs - auto data = this->dataPtr->emitter.mutable_header()->add_data(); - data->set_key(scatterRatioKey); - std::string *value = data->add_value(); - *value = _sdf->Get(scatterRatioKey); - } - - igndbg << "Loading particle emitter:" << std::endl - << this->dataPtr->emitter.DebugString() << std::endl; - - // Create components. - SdfEntityCreator sdfEntityCreator(_ecm, _eventMgr); - sdfEntityCreator.SetParent(this->dataPtr->emitterEntity, _entity); - - _ecm.CreateComponent(this->dataPtr->emitterEntity, - components::Name(this->dataPtr->emitter.name())); - - _ecm.CreateComponent(this->dataPtr->emitterEntity, - components::ParticleEmitter(this->dataPtr->emitter)); - - _ecm.CreateComponent(this->dataPtr->emitterEntity, components::Pose(pose)); - - // 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) -{ - IGN_PROFILE("ParticleEmitter::PreUpdate"); - - 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 - { - 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); - } - - igndbg << "New ParticleEmitterCmd component created" << std::endl; -} - -IGNITION_ADD_PLUGIN(ParticleEmitter, - ignition::gazebo::System, - ParticleEmitter::ISystemConfigure, - ParticleEmitter::ISystemPreUpdate) - -IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter, - "ignition::gazebo::systems::ParticleEmitter") diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh deleted file mode 100644 index 6a3da57d233..00000000000 --- a/src/systems/particle_emitter/ParticleEmitter.hh +++ /dev/null @@ -1,144 +0,0 @@ -/* - * Copyright (C) 2021 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. - * - */ -#ifndef IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ -#define IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ - -#include - -#include - -namespace ignition -{ -namespace gazebo -{ -// Inline bracket to help doxygen filtering. -inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { -namespace systems -{ - class ParticleEmitterPrivate; - - /// \brief A system for creating a particle emitter. - /// - /// This system will be deprecated in Igition Fortress. Please consider - /// using the ParticleEmitter2 system. - /// - /// System parameters - /// - /// ``: Unique name for the particle emitter. The name will be - /// automatically generated if this parameter is not set. - /// ``: Rename the particle emitter if one with the same name - /// already exists. Default is false. - /// ``: The emitter type (point, box, cylinder, ellipsoid). - /// Default value is point. - /// ``: The pose of the emitter. Default value is {0, 0, 0, 0, 0, 0}. - /// ``: The size of the emitter where the particles are sampled. - /// Default value is (1, 1, 1). - /// Note that the interpretation of the emitter area varies - /// depending on the emmiter type: - /// - point: The area is ignored. - /// - box: The area is interpreted as width X height X depth. - /// - cylinder: The area is interpreted as the bounding box of the - /// cilinder. The cylinder is oriented along the - /// Z-axis. - /// - ellipsoid: The area is interpreted as the bounding box of an - /// ellipsoid shaped area, i.e. a sphere or - /// squashed-sphere area. The parameters are again - /// identical to EM_BOX, except that the dimensions - /// describe the widest points along each of the - /// axes. - /// ``: How many particles per second should be emitted. - /// Default value is 10. - /// `: The number of seconds the emitter is active. A value of 0 - /// means infinite duration. Default value is 0. - /// ``: This is used to turn on or off particle emission. - /// Default value is false. - /// ``: Set the particle dimensions (width, height, depth). - /// Default value is {1, 1, 1}. - /// ``: Set the number of seconds each particle will ’live’ for - /// before being destroyed. Default value is 5. - /// ``: Sets the material which all particles in the emitter will - /// use. - /// ``: Sets a minimum velocity for each particle (m/s). - /// Default value is 1. - /// ``: Sets a maximum velocity for each particle (m/s). - /// Default value is 1. - /// ``: Sets the starting color for all particle emitted. - /// The actual color will be interpolated between this color - /// and the one set under . - /// 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 . - /// 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 - /// and y direction per second. Default value is 1. - /// ``: Sets the path to the color image used as an - /// affector. This affector modifies the color of - /// particles in flight. The colors are taken from a - /// specified image file. The range of color values - /// begins from the left side of the image and move to - /// the right over the lifetime of the particle, - /// therefore only the horizontal dimension of the - /// 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 ParticleEmitter - : public System, - public ISystemConfigure, - public ISystemPreUpdate - { - /// \brief Constructor - public: IGN_DEPRECATED(6) ParticleEmitter(); - - // Documentation inherited - public: void Configure(const Entity &_entity, - const std::shared_ptr &_sdf, - EntityComponentManager &_ecm, - EventManager &_eventMgr) override; - - // Documentation inherited - public: void PreUpdate( - const ignition::gazebo::UpdateInfo &_info, - ignition::gazebo::EntityComponentManager &_ecm) override; - - /// \brief Private data pointer - private: std::unique_ptr dataPtr; - }; - } -} -} -} - -#endif - From 84df8174c49cc707d51e2171e73b09d1f199156e Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:06:11 -0800 Subject: [PATCH 2/8] Copied particle_emitter2 to particle_emitter Signed-off-by: Nate Koenig --- src/systems/particle_emitter/CMakeLists.txt | 9 + .../particle_emitter/ParticleEmitter.cc | 255 ++++++++++++++++++ .../particle_emitter/ParticleEmitter.hh | 69 +++++ 3 files changed, 333 insertions(+) create mode 100644 src/systems/particle_emitter/CMakeLists.txt create mode 100644 src/systems/particle_emitter/ParticleEmitter.cc create mode 100644 src/systems/particle_emitter/ParticleEmitter.hh diff --git a/src/systems/particle_emitter/CMakeLists.txt b/src/systems/particle_emitter/CMakeLists.txt new file mode 100644 index 00000000000..9e75a90abf9 --- /dev/null +++ b/src/systems/particle_emitter/CMakeLists.txt @@ -0,0 +1,9 @@ +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 new file mode 100644 index 00000000000..5b455e11d72 --- /dev/null +++ b/src/systems/particle_emitter/ParticleEmitter.cc @@ -0,0 +1,255 @@ +/* + * Copyright (C) 2021 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 +#include + +#include +#include +#include +#include + +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include "ParticleEmitter.hh" + +using namespace std::chrono_literals; + +using namespace ignition; +using namespace gazebo; +using namespace systems; + +// Private data class. +class ignition::gazebo::systems::ParticleEmitterPrivate +{ + /// \brief Callback for receiving particle emitter commands. + /// \param[in] _msg Particle emitter message. + public: void OnCmd(const ignition::msgs::ParticleEmitter &_msg, + const transport::MessageInfo &_info); + + public: bool EmittersService(ignition::msgs::ParticleEmitter_V &_res); + + /// \brief The transport node. + public: ignition::transport::Node node; + + /// \brief Map of topic name to particle emitter entity. + public: std::map emitterTopicMap; + + /// \brief Map of Entity to particle emitter command requested externally. + public: std::map userCmd; + + /// \brief A mutex to protect the user command. + public: std::mutex mutex; + + /// \brief Protects serviceMsg. + public: std::mutex serviceMutex; + + /// \brief Filled on demand for the emitter service. + public: msgs::ParticleEmitter_V serviceMsg; +}; + +////////////////////////////////////////////////// +void ParticleEmitterPrivate::OnCmd(const msgs::ParticleEmitter &_msg, + const transport::MessageInfo &_info) +{ + std::lock_guard lock(this->mutex); + std::map::const_iterator iter = + this->emitterTopicMap.find(_info.Topic()); + if (iter != this->emitterTopicMap.end()) + { + this->userCmd[iter->second].CopyFrom(_msg); + } + else + { + ignwarn << "Topic[" << _info.Topic() << "] is not known to the particle " + "emitter system. The requested command will be ignored.\n"; + } +} + +////////////////////////////////////////////////// +bool ParticleEmitterPrivate::EmittersService( + ignition::msgs::ParticleEmitter_V &_res) +{ + _res.Clear(); + + std::scoped_lock lock(this->serviceMutex); + _res.CopyFrom(this->serviceMsg); + return true; +} + +////////////////////////////////////////////////// +ParticleEmitter::ParticleEmitter() + : System(), dataPtr(std::make_unique()) +{ +} + +////////////////////////////////////////////////// +void ParticleEmitter::Configure(const Entity &_entity, + const std::shared_ptr & /*_sdf*/, + EntityComponentManager &_ecm, + EventManager & /*_eventMgr*/) +{ + // World + const components::Name *name = _ecm.Component(_entity); + if (name == nullptr) + { + ignerr << "World with id: " << _entity + << " has no name. ParticleEmitter cannot create transport topics\n"; + return; + } + + std::string emittersService = "/world/" + name->Data() + "/particle_emitters"; + if (this->dataPtr->node.Advertise(emittersService, + &ParticleEmitterPrivate::EmittersService, this->dataPtr.get())) + { + ignmsg << "Serving particle emitter information on [" + << emittersService << "]" << std::endl; + } + else + { + ignerr << "Something went wrong, failed to advertise [" << emittersService + << "]" << std::endl; + } +} + +////////////////////////////////////////////////// +void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) +{ + IGN_PROFILE("ParticleEmitter::PreUpdate"); + + std::lock_guard lock(this->dataPtr->mutex); + + // Create particle emitters + { + std::lock_guard serviceLock(this->dataPtr->serviceMutex); + _ecm.EachNew( + [&](const Entity &_entity, + const components::ParticleEmitter *_emitter, + const components::ParentEntity *_parent, + const components::Pose *_pose)->bool + { + std::string topic; + + // Get the topic information from the header, which is currently a + // hack to avoid breaking the particle_emitter.proto message. + if (_emitter->Data().has_header()) + { + for (const auto data : _emitter->Data().header().data()) + { + if (data.key() == "topic" && !data.value().empty()) + { + topic = data.value(0); + } + } + } + + // If a topic has not been specified, then generate topic based + // on the scoped name. + topic = !topic.empty() ? topic : + topicFromScopedName(_entity, _ecm) + "/cmd"; + + // Subscribe to the topic that receives particle emitter commands. + 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 false; + } + ignmsg << "Particle emitter[" + << scopedName(_entity, _ecm, "::", false) << "] subscribed " + << "to command messages on topic[" << topic << "]\n"; + + // Store the topic name so that we can apply user commands + // correctly. + this->dataPtr->emitterTopicMap[topic] = _entity; + + // Store the emitter information in the service message, which + // can then be used in the particle_emitters service. + msgs::ParticleEmitter *emitterMsg = + this->dataPtr->serviceMsg.add_particle_emitter(); + emitterMsg->CopyFrom(_emitter->Data()); + msgs::Set(emitterMsg->mutable_pose(), _pose->Data()); + + // Set the topic information if it was not set via SDF. + if (!emitterMsg->has_header()) + { + auto headerData = emitterMsg->mutable_header()->add_data(); + headerData->set_key("topic"); + headerData->add_value(topic); + } + + // Set the particle emitter frame + auto frameData = emitterMsg->mutable_header()->add_data(); + frameData->set_key("frame"); + frameData->add_value( + removeParentScope( + scopedName(_parent->Data(), _ecm, "::", false), "::")); + + return true; + }); + } + + if (this->dataPtr->userCmd.empty() || _info.paused) + return; + + // Process each command + for (const auto cmd : this->dataPtr->userCmd) + { + // Create component. + auto emitterComp = _ecm.Component( + cmd.first); + if (!emitterComp) + { + _ecm.CreateComponent(cmd.first, + components::ParticleEmitterCmd(cmd.second)); + } + else + { + emitterComp->Data() = cmd.second; + + // 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(cmd.first, + components::ParticleEmitterCmd::typeId, + ComponentState::OneTimeChange); + } + } + this->dataPtr->userCmd.clear(); +} + +IGNITION_ADD_PLUGIN(ParticleEmitter, + ignition::gazebo::System, + ParticleEmitter::ISystemConfigure, + ParticleEmitter::ISystemPreUpdate) + +IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter, + "ignition::gazebo::systems::ParticleEmitter") diff --git a/src/systems/particle_emitter/ParticleEmitter.hh b/src/systems/particle_emitter/ParticleEmitter.hh new file mode 100644 index 00000000000..ed144dab4d0 --- /dev/null +++ b/src/systems/particle_emitter/ParticleEmitter.hh @@ -0,0 +1,69 @@ +/* + * Copyright (C) 2021 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. + * + */ +#ifndef IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ +#define IGNITION_GAZEBO_SYSTEMS_PARTICLE_EMITTER_HH_ + +#include + +#include + +namespace ignition +{ +namespace gazebo +{ +// Inline bracket to help doxygen filtering. +inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE { +namespace systems +{ + class ParticleEmitterPrivate; + + /// \brief A system for running and managing particle emitters. A particle + /// emitter is defined using the SDF element. + /// + /// This system will create a transport subscriber for each + /// using the child name. If a is not + /// specified, the following topic naming scheme will be used: + /// `/model/{model_name}/link/{link_name}/particle_emitter/{emitter_name}/cmd` + class ParticleEmitter + : public System, + public ISystemConfigure, + public ISystemPreUpdate + { + /// \brief Constructor + public: ParticleEmitter(); + + // Documentation inherited + public: void Configure(const Entity &_entity, + const std::shared_ptr &_sdf, + EntityComponentManager &_ecm, + EventManager &_eventMgr) override; + + // Documentation inherited + public: void PreUpdate( + const ignition::gazebo::UpdateInfo &_info, + ignition::gazebo::EntityComponentManager &_ecm) override; + + /// \brief Private data pointer + private: std::unique_ptr dataPtr; + }; + } +} +} +} + +#endif + From 4e39df2d241d44886d80021e09b1f812634705d3 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:08:15 -0800 Subject: [PATCH 3/8] remove particle_emitter example world and test files Signed-off-by: Nate Koenig --- examples/worlds/particle_emitter.sdf | 95 -------------- test/integration/particle_emitter.cc | 178 --------------------------- test/worlds/particle_emitter.sdf | 107 ---------------- 3 files changed, 380 deletions(-) delete mode 100644 examples/worlds/particle_emitter.sdf delete mode 100644 test/integration/particle_emitter.cc delete mode 100644 test/worlds/particle_emitter.sdf diff --git a/examples/worlds/particle_emitter.sdf b/examples/worlds/particle_emitter.sdf deleted file mode 100644 index bf372aeef24..00000000000 --- a/examples/worlds/particle_emitter.sdf +++ /dev/null @@ -1,95 +0,0 @@ - - - - - - - - - - - 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/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc deleted file mode 100644 index 0b95df94326..00000000000 --- a/test/integration/particle_emitter.cc +++ /dev/null @@ -1,178 +0,0 @@ -/* - * Copyright (C) 2021 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 - -#include - -#include - -#include -#include - -#include "ignition/gazebo/Entity.hh" -#include "ignition/gazebo/Server.hh" -#include "ignition/gazebo/SystemLoader.hh" -#include "ignition/gazebo/components/Name.hh" -#include "ignition/gazebo/components/ParticleEmitter.hh" -#include "ignition/gazebo/components/Pose.hh" -#include "ignition/gazebo/test_config.hh" - -#include "helpers/EnvTestFixture.hh" -#include "helpers/Relay.hh" - -using namespace ignition; -using namespace gazebo; - -class ParticleEmitterTest : public InternalFixture<::testing::Test> -{ - public: void LoadWorld(const std::string &_path, bool _useLevels = false) - { - this->serverConfig.SetSdfFile( - common::joinPaths(PROJECT_SOURCE_PATH, _path)); - this->serverConfig.SetUseLevels(_useLevels); - - this->server = std::make_unique(this->serverConfig); - EXPECT_FALSE(this->server->Running()); - EXPECT_FALSE(*this->server->Running(0)); - using namespace std::chrono_literals; - this->server->SetUpdatePeriod(1ns); - } - - public: ServerConfig serverConfig; - public: std::unique_ptr server; -}; - -///////////////////////////////////////////////// -// Load an SDF with a particle emitter and verify its properties. -TEST_F(ParticleEmitterTest, SDFLoad) -{ - bool updateCustomChecked{false}; - bool updateDefaultChecked{false}; - - this->LoadWorld("test/worlds/particle_emitter.sdf"); - - // Create a system that checks a particle emitter. - test::Relay testSystem; - testSystem.OnPostUpdate([&](const gazebo::UpdateInfo &, - const gazebo::EntityComponentManager &_ecm) - { - _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, - const components::ParticleEmitter *_emitter, - const components::Name *_name, - const components::Pose *_pose) -> bool - { - - if (_name->Data() == "smoke_emitter") - { - updateCustomChecked = true; - - EXPECT_EQ("smoke_emitter", _name->Data()); - EXPECT_EQ(_name->Data(), _emitter->Data().name()); - EXPECT_EQ(msgs::ParticleEmitter_EmitterType_BOX, - _emitter->Data().type()); - EXPECT_EQ(math::Pose3d(0, 1, 0, 0, 0, 0), _pose->Data()); - EXPECT_EQ(_pose->Data(), - 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().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().data()); - // TODO(anyone) add material check here - 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().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().data()); - - // particle scatter ratio is temporarily stored in header - bool hasParticleScatterRatio = false; - for (int i = 0; i < _emitter->Data().header().data_size(); ++i) - { - for (int j = 0; - j < _emitter->Data().header().data(i).value_size(); ++j) - { - if (_emitter->Data().header().data(i).key() == - "particle_scatter_ratio") - { - EXPECT_DOUBLE_EQ(0.01, math::parseFloat( - _emitter->Data().header().data(i).value(0))); - hasParticleScatterRatio = true; - } - } - } - EXPECT_TRUE(hasParticleScatterRatio); - } - else - { - updateDefaultChecked = true; - - EXPECT_TRUE(_name->Data().find(std::to_string(_entity)) - != std::string::npos); - EXPECT_EQ(_name->Data(), _emitter->Data().name()); - EXPECT_EQ(msgs::ParticleEmitter_EmitterType_POINT, - _emitter->Data().type()); - EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); - EXPECT_EQ(_pose->Data(), - 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().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().data()); - // TODO(anyone) add material check here - 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().data()); - EXPECT_EQ("", _emitter->Data().color_range_image().data()); - } - - return true; - }); - }); - - this->server->AddSystem(testSystem.systemPtr); - this->server->Run(true, 1, false); - - EXPECT_TRUE(updateCustomChecked); - EXPECT_TRUE(updateDefaultChecked); -} diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf deleted file mode 100644 index 0d15a8c2dc0..00000000000 --- a/test/worlds/particle_emitter.sdf +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - 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 - - - - - - - - 0 0 0 0 0 0 - true - - - - - 1 1 1 - - - - - - - smoke_emitter - box - 0 1 0 0 0 0 - 2 2 2 - 5 - 1 - true - 3 3 3 - 2 - - 10 - 20 - 0 0 1 - 0 1 0 - 10 - /path/to/dummy_image.png - 0.01 - - - - - - 5 5 0 0 0 0 - true - - - - - 1 1 1 - - - - - - - - - - - - From c4995167b882e51e91d7d0c14da2226c697f9b3b Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:09:33 -0800 Subject: [PATCH 4/8] Moved particle_emitter2 example world and test files to particle_emitter Signed-off-by: Nate Koenig --- examples/worlds/{particle_emitter2.sdf => particle_emitter.sdf} | 0 test/integration/{particle_emitter2.cc => particle_emitter.cc} | 0 test/worlds/{particle_emitter2.sdf => particle_emitter.sdf} | 0 3 files changed, 0 insertions(+), 0 deletions(-) rename examples/worlds/{particle_emitter2.sdf => particle_emitter.sdf} (100%) rename test/integration/{particle_emitter2.cc => particle_emitter.cc} (100%) rename test/worlds/{particle_emitter2.sdf => particle_emitter.sdf} (100%) diff --git a/examples/worlds/particle_emitter2.sdf b/examples/worlds/particle_emitter.sdf similarity index 100% rename from examples/worlds/particle_emitter2.sdf rename to examples/worlds/particle_emitter.sdf diff --git a/test/integration/particle_emitter2.cc b/test/integration/particle_emitter.cc similarity index 100% rename from test/integration/particle_emitter2.cc rename to test/integration/particle_emitter.cc diff --git a/test/worlds/particle_emitter2.sdf b/test/worlds/particle_emitter.sdf similarity index 100% rename from test/worlds/particle_emitter2.sdf rename to test/worlds/particle_emitter.sdf From cc6765190cda4c7ef01756752b971953774feacc Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:12:19 -0800 Subject: [PATCH 5/8] renamed emitter2 to emitter in example world and tests Signed-off-by: Nate Koenig --- examples/worlds/particle_emitter.sdf | 4 ++-- test/integration/particle_emitter.cc | 6 +++--- test/worlds/particle_emitter.sdf | 10 ++++------ 3 files changed, 9 insertions(+), 11 deletions(-) diff --git a/examples/worlds/particle_emitter.sdf b/examples/worlds/particle_emitter.sdf index 8995d3fe464..36fae35919d 100644 --- a/examples/worlds/particle_emitter.sdf +++ b/examples/worlds/particle_emitter.sdf @@ -42,8 +42,8 @@ name="ignition::gazebo::systems::SceneBroadcaster"> + filename="ignition-gazebo-particle-emitter-system" + name="ignition::gazebo::systems::ParticleEmitter"> diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index d8b4922c7bc..24ddbc1c82c 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -37,7 +37,7 @@ using namespace ignition; using namespace gazebo; -class ParticleEmitter2Test : public InternalFixture<::testing::Test> +class ParticleEmitterTest : public InternalFixture<::testing::Test> { public: void LoadWorld(const std::string &_path, bool _useLevels = false) { @@ -58,12 +58,12 @@ class ParticleEmitter2Test : public InternalFixture<::testing::Test> ///////////////////////////////////////////////// // Load an SDF with a particle emitter and verify its properties. -TEST_F(ParticleEmitter2Test, SDFLoad) +TEST_F(ParticleEmitterTest, SDFLoad) { bool updateCustomChecked{false}; bool updateDefaultChecked{false}; - this->LoadWorld("test/worlds/particle_emitter2.sdf"); + this->LoadWorld("test/worlds/particle_emitter.sdf"); // Create a system that checks a particle emitter. test::Relay testSystem; diff --git a/test/worlds/particle_emitter.sdf b/test/worlds/particle_emitter.sdf index 4b32c57574d..9408144425c 100644 --- a/test/worlds/particle_emitter.sdf +++ b/test/worlds/particle_emitter.sdf @@ -8,8 +8,8 @@ + filename="ignition-gazebo-particle-emitter-system" + name="ignition::gazebo::systems::ParticleEmitter"> @@ -97,11 +97,9 @@ + + - - - From 3038fe0de95db9f30c3540c8a060822e7cbd671d Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:14:48 -0800 Subject: [PATCH 6/8] Fix integration test Signed-off-by: Nate Koenig --- test/integration/CMakeLists.txt | 1 - test/integration/particle_emitter.cc | 10 ++++------ 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/test/integration/CMakeLists.txt b/test/integration/CMakeLists.txt index e09452bbad5..d5378a979ad 100644 --- a/test/integration/CMakeLists.txt +++ b/test/integration/CMakeLists.txt @@ -42,7 +42,6 @@ set(tests network_handshake.cc odometry_publisher.cc particle_emitter.cc - particle_emitter2.cc performer_detector.cc physics_system.cc play_pause.cc diff --git a/test/integration/particle_emitter.cc b/test/integration/particle_emitter.cc index 24ddbc1c82c..ada18c5f7b4 100644 --- a/test/integration/particle_emitter.cc +++ b/test/integration/particle_emitter.cc @@ -73,7 +73,7 @@ TEST_F(ParticleEmitterTest, SDFLoad) _ecm.Each( - [&](const ignition::gazebo::Entity &_entity, + [&](const ignition::gazebo::Entity &, const components::ParticleEmitter *_emitter, const components::Name *_name, const components::Pose *_pose) -> bool @@ -121,9 +121,7 @@ TEST_F(ParticleEmitterTest, SDFLoad) { updateDefaultChecked = true; - EXPECT_TRUE(_name->Data().find(std::to_string(_entity)) - != std::string::npos); - EXPECT_EQ(_name->Data(), _emitter->Data().name()); + EXPECT_EQ("smoke_generator", _name->Data()); EXPECT_EQ(msgs::ParticleEmitter_EmitterType_POINT, _emitter->Data().type()); EXPECT_EQ(math::Pose3d(0, 0, 0, 0, 0, 0), _pose->Data()); @@ -133,7 +131,7 @@ TEST_F(ParticleEmitterTest, SDFLoad) msgs::Convert(_emitter->Data().size())); 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_TRUE(_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().data()); @@ -144,7 +142,7 @@ TEST_F(ParticleEmitterTest, SDFLoad) 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().data()); + EXPECT_DOUBLE_EQ(0.0, _emitter->Data().scale_rate().data()); EXPECT_EQ("", _emitter->Data().color_range_image().data()); } From deaf1b1a7d11721c67b50411a49ee3e31736fa73 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Wed, 12 Jan 2022 11:23:29 -0800 Subject: [PATCH 7/8] Update tutorial and example world Signed-off-by: Nate Koenig --- examples/worlds/multi_lrauv_race.sdf | 10 ++-------- tutorials/particle_tutorial.md | 10 +++++----- 2 files changed, 7 insertions(+), 13 deletions(-) diff --git a/examples/worlds/multi_lrauv_race.sdf b/examples/worlds/multi_lrauv_race.sdf index 717bf861802..a936210dd97 100644 --- a/examples/worlds/multi_lrauv_race.sdf +++ b/examples/worlds/multi_lrauv_race.sdf @@ -38,12 +38,9 @@ 1000 - + filename="ignition-gazebo-particle-emitter-system" + name="ignition::gazebo::systems::ParticleEmitter"> @@ -60,9 +57,6 @@ -0.5 0.1 -0.9 - -5 0 0 0 0 0 https://fuel.ignitionrobotics.org/1.0/mabel/models/Turquoise turbidity generator diff --git a/tutorials/particle_tutorial.md b/tutorials/particle_tutorial.md index d15049b9fff..dc6ab9f28eb 100644 --- a/tutorials/particle_tutorial.md +++ b/tutorials/particle_tutorial.md @@ -4,15 +4,15 @@ This tutorial shows how to use the particle emitter system to add and configure ## Particle Emitter System -We will demonstrate the particle emitter system by using the [examples/worlds/particle_emitter2.sdf]( -https://github.com/ignitionrobotics/ign-gazebo/blob/ign-gazebo4/examples/worlds/particle_emitter2.sdf) world. +We will demonstrate the particle emitter system by using the [examples/worlds/particle_emitter.sdf]( +https://github.com/ignitionrobotics/ign-gazebo/blob/main/examples/worlds/particle_emitter.sdf) world. To be able to spawn particle emitters, first you will need to include the particle emitter system as a plugin to the world in your SDF. The system does not take any arguments. ```xml + filename="ignition-gazebo-particle-emitter-system" + name="ignition::gazebo::systems::ParticleEmitter"> ``` @@ -60,7 +60,7 @@ The SDF 1.6+ specification supports having a `` SDF element as Let's launch the example world to see what it looks like. ```bash -ign gazebo -v 4 -r particle_emitter2.sdf +ign gazebo -v 4 -r particle_emitter.sdf ``` You should see the fog slowly starting to appear from the ground plane in the world: From 9f7648aa3ca5c497045f45d42339e0b0618fe455 Mon Sep 17 00:00:00 2001 From: Nate Koenig Date: Mon, 14 Feb 2022 09:10:13 -0800 Subject: [PATCH 8/8] Updated migration guide, and deprecated ParticleEmitter2 Signed-off-by: Nate Koenig --- Migration.md | 7 +++++++ src/systems/particle_emitter2/ParticleEmitter2.hh | 5 +++-- 2 files changed, 10 insertions(+), 2 deletions(-) diff --git a/Migration.md b/Migration.md index 4fbe67cda46..1bf5bf5286d 100644 --- a/Migration.md +++ b/Migration.md @@ -5,6 +5,13 @@ Deprecated code produces compile-time warnings. These warning serve as notification to users that their code should be upgraded. The next major release will remove the deprecated code. +## Ignition Gazebo 6.x to 7.0 + +* **Deprecated** + + The `ParticleEmitter2` system was renamed to `ParticleEmitter`. The + `ParticleEmitter2` system is now deprecated. Please use the + `ParticleEmitter` system. + ## Ignition Gazebo 6.1 to 6.2 * If no `` is given to the `Thruster` plugin, the namespace now diff --git a/src/systems/particle_emitter2/ParticleEmitter2.hh b/src/systems/particle_emitter2/ParticleEmitter2.hh index a52d39f65ff..e9dd359d004 100644 --- a/src/systems/particle_emitter2/ParticleEmitter2.hh +++ b/src/systems/particle_emitter2/ParticleEmitter2.hh @@ -31,7 +31,8 @@ namespace systems { class ParticleEmitter2Private; - /// \brief A system for running and managing particle emitters. A particle + /// \brief This is deprecated, please use the ParticleEmitter system. + /// A system for running and managing particle emitters. A particle /// emitter is defined using the SDF element. /// /// This system will create a transport subscriber for each @@ -51,7 +52,7 @@ namespace systems public ISystemPreUpdate { /// \brief Constructor - public: ParticleEmitter2(); + public: IGN_DEPRECATED(7) ParticleEmitter2(); // Documentation inherited public: void Configure(const Entity &_entity,