Skip to content
Merged
Show file tree
Hide file tree
Changes from 8 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
1 change: 1 addition & 0 deletions src/systems/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -95,6 +95,7 @@ add_subdirectory(magnetometer)
add_subdirectory(multicopter_motor_model)
add_subdirectory(multicopter_control)
add_subdirectory(optical_tactile_plugin)
add_subdirectory(particle_emitter)
add_subdirectory(performer_detector)
add_subdirectory(physics)
add_subdirectory(pose_publisher)
Expand Down
6 changes: 6 additions & 0 deletions src/systems/particle_emitter/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
gz_add_system(particle-emitter
SOURCES
ParticleEmitter.cc
PUBLIC_LINK_LIBS
ignition-msgs${IGN_MSGS_VER}::ignition-msgs${IGN_MSGS_VER}
)
186 changes: 186 additions & 0 deletions src/systems/particle_emitter/ParticleEmitter.cc
Original file line number Diff line number Diff line change
@@ -0,0 +1,186 @@
/*
* 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 <ignition/msgs/particle_emitter.pb.h>

#include <string>

#include <ignition/common/Profiler.hh>
#include <ignition/msgs/Utility.hh>
#include <ignition/plugin/Register.hh>

#include <ignition/gazebo/components/Name.hh>
#include <ignition/gazebo/components/ParticleEmitter.hh>
#include <ignition/gazebo/components/Pose.hh>
#include <ignition/gazebo/Conversions.hh>
#include <sdf/Material.hh>
#include "ParticleEmitter.hh"

using namespace ignition;
using namespace gazebo;
using namespace systems;

// Private data class.
class ignition::gazebo::systems::ParticleEmitterPrivate
{
/// \brief The particle emitter.
public: ignition::msgs::ParticleEmitter emitter;
};

//////////////////////////////////////////////////
ParticleEmitter::ParticleEmitter()
: System(), dataPtr(std::make_unique<ParticleEmitterPrivate>())
{
}

//////////////////////////////////////////////////
void ParticleEmitter::Configure(const Entity &/*_entity*/,
const std::shared_ptr<const sdf::Element> &_sdf,
EntityComponentManager &_ecm,
EventManager &/*_eventMgr*/)
{
// Create a particle emitter entity.
auto entity = _ecm.CreateEntity();
if (entity == kNullEntity)
{
ignerr << "Failed to create a particle emitter entity" << std::endl;
return;
}

// Name.
std::string name = "particle_emitter_entity_" + std::to_string(entity);
if (_sdf->HasElement("emitter_name"))
name = _sdf->Get<std::string>("emitter_name");
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<std::string>("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<ignition::math::Pose3d>("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<ignition::math::Vector3d>("size");
ignition::msgs::Set(this->dataPtr->emitter.mutable_size(), size);

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

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

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

// Particle size.
size = ignition::math::Vector3d::One;
if (_sdf->HasElement("particle_size"))
size = _sdf->Get<ignition::math::Vector3d>("particle_size");
ignition::msgs::Set(this->dataPtr->emitter.mutable_particle_size(), size);

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

// Material.
if (_sdf->HasElement("material"))
{
auto materialElem = _sdf->GetElementImpl("material");
sdf::Material material;
material.Load(materialElem);
ignition::msgs::Material materialMsg = convert<msgs::Material>(material);
}

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

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

// Color start.
ignition::math::Color color = ignition::math::Color::White;
if (_sdf->HasElement("color_start"))
color = _sdf->Get<ignition::math::Color>("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<ignition::math::Color>("color_end");
ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), color);

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

// Color range image.
this->dataPtr->emitter.set_color_range_image(
_sdf->Get<std::string>("color_range_image", "").first);

igndbg << "Loading particle emitter:" << std::endl
<< this->dataPtr->emitter.DebugString() << std::endl;

// Create components.
_ecm.CreateComponent(entity, components::Name(this->dataPtr->emitter.name()));

_ecm.CreateComponent(entity,
components::ParticleEmitter(this->dataPtr->emitter));

_ecm.CreateComponent(entity, components::Pose(pose));
}

//////////////////////////////////////////////////
void ParticleEmitter::PreUpdate(const ignition::gazebo::UpdateInfo &/*_info*/,
ignition::gazebo::EntityComponentManager &/*_ecm*/)
{
IGN_PROFILE("ParticleEmitter::PreUpdate");
}

IGNITION_ADD_PLUGIN(ParticleEmitter,
ignition::gazebo::System,
ParticleEmitter::ISystemConfigure,
ParticleEmitter::ISystemPreUpdate)

IGNITION_ADD_PLUGIN_ALIAS(ParticleEmitter,
"ignition::gazebo::systems::ParticleEmitter")
128 changes: 128 additions & 0 deletions src/systems/particle_emitter/ParticleEmitter.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,128 @@
/*
* 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 <memory>

#include <ignition/gazebo/System.hh>

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.
///
/// System parameters
///
/// `<emitter_name>`: Unique name for the particle emitter. The name will be
/// automatically generated if this parameter is not set.
/// `<type>`: The emitter type (point, box, cylinder, ellipsoid).
/// Default value is point.
/// `<pose>`: The pose of the emitter. Default value is {0, 0, 0, 0, 0, 0}.
/// `<size>`: 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.
/// `<rate>`: How many particles per second should be emitted.
/// Default value is 10.
/// `<duration`>: The number of seconds the emitter is active. A value of 0
/// means infinite duration. Default value is 0.
/// `<emitting>`: This is used to turn on or off particle emission.
/// Default value is false.
/// `<particle_size>`: Set the particle dimensions (width, height, depth).
/// Default value is {1, 1, 1}.
/// `<lifetime>`: Set the number of seconds each particle will ’live’ for
/// before being destroyed. Default value is 5.
/// `<material>`: Sets the material which all particles in the emitter will
/// use.
/// `<min_velocity>`: Sets a minimum velocity for each particle (m/s).
/// Default value is 1.
/// `<max_velocity>`: Sets a maximum velocity for each particle (m/s).
/// Default value is 1.
/// `<color_start>`: Sets the starting color for all particle emitted.
/// The actual color will be interpolated between this color
/// and the one set under <color_end>.
/// Color::White is the default color for the particles
/// unless a specific function is used.
/// Note that this function overrides the particle colors set
/// with <ColorRangeImage>.
/// `<color_end>`: Sets the end color for all particle emitted.
/// The actual color will be interpolated between this color
/// and the one set under <color_start>.
/// Color::White is the default color for the particles
/// unless a specific function is used.
/// Note that this function overrides the particle colors set
/// with <ColorRangeImage>.
/// `<scale_rate>`: Sets the amount by which to scale the particles in both x
/// and y direction per second. Default value is 1.
/// `<color_range_image>`: 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 <color_start> and <color_end>.
class IGNITION_GAZEBO_VISIBLE ParticleEmitter
: public System,
public ISystemConfigure,
public ISystemPreUpdate
{
/// \brief Constructor
public: ParticleEmitter();

// Documentation inherited
public: void Configure(const Entity &_entity,
const std::shared_ptr<const sdf::Element> &_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<ParticleEmitterPrivate> dataPtr;
};
}
}
}
}

#endif

1 change: 1 addition & 0 deletions test/integration/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,7 @@ set(tests
model.cc
multicopter.cc
network_handshake.cc
particle_emitter.cc
performer_detector.cc
physics_system.cc
play_pause.cc
Expand Down
Loading