Gazebo Rendering

API Reference

6.6.3
gz/rendering/ParticleEmitter.hh
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2020 Open Source Robotics Foundation
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  *
16  */
17 #ifndef IGNITION_RENDERING_PARTICLEEMITTER_HH_
18 #define IGNITION_RENDERING_PARTICLEEMITTER_HH_
19 
20 #include <string>
21 #include "ignition/math/Color.hh"
22 #include "ignition/math/Pose3.hh"
23 #include "ignition/math/Vector3.hh"
28 
29 namespace ignition
30 {
31  namespace rendering
32  {
33  inline namespace IGNITION_RENDERING_VERSION_NAMESPACE {
34  //
36  enum IGNITION_RENDERING_VISIBLE EmitterType
37  {
39  EM_POINT = 0,
40 
42  EM_BOX = 1,
43 
46 
49 
52  };
53 
56  //
58  class IGNITION_RENDERING_VISIBLE ParticleEmitter :
59  public virtual Visual
60  {
62  public: virtual ~ParticleEmitter() {}
63 
68  public: virtual EmitterType Type() const = 0;
69 
75  public: virtual void SetType(const EmitterType _type) = 0;
76 
81  public: virtual ignition::math::Vector3d EmitterSize() const = 0;
82 
98  public: virtual void SetEmitterSize(
99  const ignition::math::Vector3d &_size) = 0;
100 
104  public: virtual double Rate() const = 0;
105 
110  public: virtual void SetRate(double _rate) = 0;
111 
116  public: virtual double Duration() const = 0;
117 
123  public: virtual void SetDuration(double _duration) = 0;
124 
128  public: virtual bool Emitting() const = 0;
129 
134  public: virtual void SetEmitting(bool _enable) = 0;
135 
139  public: virtual ignition::math::Vector3d ParticleSize() const = 0;
140 
145  public: virtual void SetParticleSize(
146  const ignition::math::Vector3d &_size) = 0;
147 
152  public: virtual double Lifetime() const = 0;
153 
159  public: virtual void SetLifetime(double _lifetime) = 0;
160 
164  public: virtual MaterialPtr Material() const = 0;
165 
169  public: virtual void SetMaterial(const MaterialPtr &_material) = 0;
170 
175  public: virtual double MinVelocity() const = 0;
176 
181  public: virtual double MaxVelocity() const = 0;
182 
190  public: virtual void SetVelocityRange(double _minVelocity,
191  double _maxVelocity) = 0;
192 
197  public: virtual ignition::math::Color ColorStart() const = 0;
198 
203  public: virtual ignition::math::Color ColorEnd() const = 0;
204 
215  public: virtual void SetColorRange(
216  const ignition::math::Color &_colorStart,
217  const ignition::math::Color &_colorEnd) = 0;
218 
224  public: virtual double ScaleRate() const = 0;
225 
230  public: virtual void SetScaleRate(double _scaleRate) = 0;
231 
235  public: virtual std::string ColorRangeImage() const = 0;
236 
247  public: virtual void SetColorRangeImage(const std::string &_image) = 0;
248 
252  public: virtual float ParticleScatterRatio() const = 0;
253 
258  public: virtual void SetParticleScatterRatio(float _ratio) = 0;
259  };
260  }
261  }
262 }
263 #endif
STL class.
STL class.
@ EM_BOX
Box emitter.
Definition: gz/rendering/ParticleEmitter.hh:42
virtual bool Emitting() const =0
Is the particle emitter enabled?
virtual void SetParticleSize(const ignition::math::Vector3d &_size)=0
Set the particle dimensions (width, height, depth). Default value is {1, 1, 1}.
virtual ignition::math::Vector3d EmitterSize() const =0
Get the size of the emitter where the particles are sampled.
virtual ignition::math::Color ColorEnd() const =0
Get the end color of the particles.
virtual void SetType(const EmitterType _type)=0
Set the emitter type. Default value is EM_POINT.
virtual void SetColorRangeImage(const std::string &_image)=0
Set the path to the color image used as an affector. This affector modifies the color of particles in...
@ EM_POINT
Point emitter.
Definition: gz/rendering/ParticleEmitter.hh:39
virtual double Duration() const =0
Get the number of seconds the emitter is active. A value of 0 means infinite duration.
virtual void SetParticleScatterRatio(float _ratio)=0
Set the particle scatter ratio.
virtual double Lifetime() const =0
Get the number of seconds each particle will ’live’ for before being destroyed.
virtual double MinVelocity() const =0
Get the minimum velocity each particle is emitted (m/s).
virtual std::string ColorRangeImage() const =0
Get the path to the color image used as an affector.
virtual void SetEmitting(bool _enable)=0
This is used to turn on or off particle emission. Default value is false.
virtual float ParticleScatterRatio() const =0
Get the particle scatter ratio.
virtual ~ParticleEmitter()
Destructor.
Definition: gz/rendering/ParticleEmitter.hh:62
virtual void SetLifetime(double _lifetime)=0
Set the number of seconds each particle will ’live’ for before being destroyed. Default value is 5.
@ EM_CYLINDER
Cylinder emitter.
Definition: gz/rendering/ParticleEmitter.hh:45
@ EM_NUM_EMITTERS
Total number of emitters (keep always at the end).
Definition: gz/rendering/ParticleEmitter.hh:51
Represents a visual node in a scene graph. A Visual is the only node that can have Geometry and other...
Definition: gz/rendering/Visual.hh:33
virtual void SetDuration(double _duration)=0
Set the number of seconds the emitter is active. A value of 0 means infinite duration....
virtual void SetColorRange(const ignition::math::Color &_colorStart, const ignition::math::Color &_colorEnd)=0
Sets a color for all particle emitted. The actual color will be interpolated between these two colors...
virtual MaterialPtr Material() const =0
Get the material which all particles in the emitter will use.
virtual EmitterType Type() const =0
Get the emitter type.
virtual void SetEmitterSize(const ignition::math::Vector3d &_size)=0
Set the size of the emitter where the particles are sampled. Default value is (1, 1,...
virtual void SetVelocityRange(double _minVelocity, double _maxVelocity)=0
Set a velocity range and each particle is emitted with a random velocity within this range (m/s)....
virtual double Rate() const =0
Get how many particles per second should be emitted.
@ EM_ELLIPSOID
Ellipsoid emitter.
Definition: gz/rendering/ParticleEmitter.hh:48
virtual void SetScaleRate(double _scaleRate)=0
Set the amount by which to scale the particles in both x and y direction per second.
virtual void SetMaterial(const MaterialPtr &_material)=0
Sets the material which all particles in the emitter will use.
Class to manage a particle emitter.
Definition: gz/rendering/ParticleEmitter.hh:58
virtual double MaxVelocity() const =0
Get the maximum velocity each particle is emitted (m/s).
virtual ignition::math::Vector3d ParticleSize() const =0
Get the particle dimensions (width, height, depth).
virtual ignition::math::Color ColorStart() const =0
Get the starting color of the particles.
Represents a surface material of a Geometry.
Definition: gz/rendering/Material.hh:47
EmitterType
Enum for emitter types.
Definition: gz/rendering/ParticleEmitter.hh:36
virtual void SetRate(double _rate)=0
Set how many particles per second should be emitted. Default value is 10.
virtual double ScaleRate() const =0
Get the amount by which to scale the particles in both x and y direction per second....