Skip to content

Commit

Permalink
Particle system - Part 1 (#516)
Browse files Browse the repository at this point in the history
* New ParticleEmitter component.

Signed-off-by: Carlos Agüero <[email protected]>

* Remove attribute name.

Signed-off-by: Carlos Agüero <[email protected]>

* Update particle emitter component to use ignition::msgs::ParticleEmitter.

Signed-off-by: Carlos Agüero <[email protected]>

* Simplify particle emitter component.

Signed-off-by: Carlos Agüero <[email protected]>

* Particle system - Part2 (#562)

Signed-off-by: Carlos Agüero <[email protected]>

Co-authored-by: Ashton Larkin <[email protected]>
Co-authored-by: Ian Chen <[email protected]>

* bump msgs version to 6.3.0

Signed-off-by: Ian Chen <[email protected]>

* Remove extra main

Signed-off-by: Nate Koenig <[email protected]>

* Added missing <set>

Signed-off-by: Nate Koenig <[email protected]>

Co-authored-by: Ashton Larkin <[email protected]>
Co-authored-by: Ian Chen <[email protected]>
Co-authored-by: Ashton Larkin <[email protected]>
Co-authored-by: Nate Koenig <[email protected]>
  • Loading branch information
5 people authored Feb 18, 2021
2 parents 44a6713 + 04721d3 commit deddb6f
Show file tree
Hide file tree
Showing 15 changed files with 1,331 additions and 17 deletions.
4 changes: 2 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@ cmake_minimum_required(VERSION 3.5.1 FATAL_ERROR)
#============================================================================
# Initialize the project
#============================================================================
project(ignition-gazebo4 VERSION 4.4.0)
project(ignition-gazebo4 VERSION 4.5.0)

#============================================================================
# Find ignition-cmake
Expand Down Expand Up @@ -53,7 +53,7 @@ set(IGN_TRANSPORT_VER ${ignition-transport9_VERSION_MAJOR})

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

#--------------------------------------
Expand Down
20 changes: 20 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,25 @@
## Ignition Gazebo 4.x

### Ignition Gazebo 4.5.0 (2020-02-17)

1. Added particle system.
* [Pull Request 516](https://github.com/ignitionrobotics/ign-gazebo/pull/516)

1. Add Light Usercommand and include Light parameters in the componentInspector
* [Pull Request 482](https://github.com/ignitionrobotics/ign-gazebo/pull/482)

1. Added link to HW-accelerated video recording.
* [Pull Request 627](https://github.com/ignitionrobotics/ign-gazebo/pull/627)

1. Fix EntityComponentManager race condition.
* [Pull Request 601](https://github.com/ignitionrobotics/ign-gazebo/pull/601)

1. Add SDF topic validity check.
* [Pull Request 632](https://github.com/ignitionrobotics/ign-gazebo/pull/632)

1. Add JointTrajectoryController system plugin.
* [Pull Request 473](https://github.com/ignitionrobotics/ign-gazebo/pull/473)

### Ignition Gazebo 4.4.0 (2020-02-10)

1. Added issue and PR templates
Expand Down
90 changes: 90 additions & 0 deletions examples/worlds/particle_emitter.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,90 @@
<?xml version="1.0" ?>

<!--
Launch this example with:
ign gazebo -r particle_emitter.sdf
Try modifying some parameters of the emitter:
To disable the particle emitter:
ign topic -t /model/smoke_generator/particle_emitter/smoke_generator -m ignition.msgs.ParticleEmitter -p 'name: "smoke_generator" pose { position { } orientation { w: 1 } } size { x: 1 y: 1 z: 1 } rate: 10 emitting: false particle_size { x: 1 y: 1 z: 1 } lifetime: 2 material { header { data { key: "double_sided" value: "0" } } ambient { a: 1 } diffuse { r: 0.7 g: 0.7 b: 0.7 a: 1 } specular { a: 1 } emissive { a: 1 } lighting: true pbr { type: METAL albedo_map: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smoke.png" metalness: 0.5 roughness: 0.5 } } min_velocity: 10 max_velocity: 20 color_start { r: 1 g: 1 b: 1 a: 1 } color_end { r: 1 g: 1 b: 1 a: 1 } scale_rate: 10 color_range_image: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smokecolors.png"'
Enable back the particle emitter:
ign topic -t /model/smoke_generator/particle_emitter/smoke_generator -m ignition.msgs.ParticleEmitter -p 'name: "smoke_generator" pose { position { } orientation { w: 1 } } size { x: 1 y: 1 z: 1 } rate: 10 emitting: true particle_size { x: 1 y: 1 z: 1 } lifetime: 2 material { header { data { key: "double_sided" value: "0" } } ambient { a: 1 } diffuse { r: 0.7 g: 0.7 b: 0.7 a: 1 } specular { a: 1 } emissive { a: 1 } lighting: true pbr { type: METAL albedo_map: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smoke.png" metalness: 0.5 roughness: 0.5 } } min_velocity: 10 max_velocity: 20 color_start { r: 1 g: 1 b: 1 a: 1 } color_end { r: 1 g: 1 b: 1 a: 1 } scale_rate: 10 color_range_image: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smokecolors.png"'
Then, change the particle rate:
ign topic -t /model/smoke_generator/particle_emitter/smoke_generator -m ignition.msgs.ParticleEmitter -p 'name: "smoke_generator" pose { position { } orientation { w: 1 } } size { x: 1 y: 1 z: 1 } rate: 100 emitting: true particle_size { x: 1 y: 1 z: 1 } lifetime: 2 material { header { data { key: "double_sided" value: "0" } } ambient { a: 1 } diffuse { r: 0.7 g: 0.7 b: 0.7 a: 1 } specular { a: 1 } emissive { a: 1 } lighting: true pbr { type: METAL albedo_map: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smoke.png" metalness: 0.5 roughness: 0.5 } } min_velocity: 10 max_velocity: 20 color_start { r: 1 g: 1 b: 1 a: 1 } color_end { r: 1 g: 1 b: 1 a: 1 } scale_rate: 10 color_range_image: "/home/caguero/.ignition/fuel/fuel.ignitionrobotics.org/caguero/models/smoke_generator/2/materials/textures/smokecolors.png"'
-->

<sdf version="1.6">
<world name="particle_emitters">

<physics name="1ms" type="ode">
<max_step_size>0.001</max_step_size>
<real_time_factor>1.0</real_time_factor>
</physics>
<plugin
filename="ignition-gazebo-physics-system"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="ignition-gazebo-user-commands-system"
name="ignition::gazebo::systems::UserCommands">
</plugin>
<plugin
filename="ignition-gazebo-scene-broadcaster-system"
name="ignition::gazebo::systems::SceneBroadcaster">
</plugin>

<light type="directional" name="sun">
<cast_shadows>true</cast_shadows>
<pose>0 0 10 0 0 0</pose>
<diffuse>1 1 1 1</diffuse>
<specular>0.5 0.5 0.5 1</specular>
<attenuation>
<range>1000</range>
<constant>0.9</constant>
<linear>0.01</linear>
<quadratic>0.001</quadratic>
</attenuation>
<direction>-0.5 0.1 -0.9</direction>
</light>

<model name="ground_plane">
<static>true</static>
<link name="link">
<collision name="collision">
<geometry>
<plane>
<normal>0 0 1</normal>
</plane>
</geometry>
</collision>
<visual name="visual">
<geometry>
<plane>
<normal>0 0 1</normal>
<size>100 100</size>
</plane>
</geometry>
<material>
<ambient>0.8 0.8 0.8 1</ambient>
<diffuse>0.8 0.8 0.8 1</diffuse>
<specular>0.8 0.8 0.8 1</specular>
</material>
</visual>
</link>
</model>

<include>
<uri>https://fuel.ignitionrobotics.org/1.0/caguero/models/smoke_generator</uri>
</include>

</world>
</sdf>


52 changes: 52 additions & 0 deletions include/ignition/gazebo/components/ParticleEmitter.hh
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
/*
* 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_COMPONENTS_PARTICLEEMITTER_HH_
#define IGNITION_GAZEBO_COMPONENTS_PARTICLEEMITTER_HH_

#include <ignition/msgs/particle_emitter.pb.h>
#include <ignition/gazebo/components/Component.hh>
#include <ignition/gazebo/components/Factory.hh>
#include <ignition/gazebo/components/Serialization.hh>
#include <ignition/gazebo/config.hh>

namespace ignition
{
namespace gazebo
{
// Inline bracket to help doxygen filtering.
inline namespace IGNITION_GAZEBO_VERSION_NAMESPACE {
namespace components
{
/// \brief A component that contains a particle emitter.
using ParticleEmitter = Component<msgs::ParticleEmitter,
class ParticleEmitterTag,
serializers::MsgSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitter",
ParticleEmitter)

/// \brief A component that contains a particle emitter command.
using ParticleEmitterCmd = Component<msgs::ParticleEmitter,
class ParticleEmitterCmdTag,
serializers::MsgSerializer>;
IGN_GAZEBO_REGISTER_COMPONENT("ign_gazebo_components.ParticleEmitterCmd",
ParticleEmitterCmd)
}
}
}
}

#endif
17 changes: 17 additions & 0 deletions include/ignition/gazebo/rendering/SceneManager.hh
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,8 @@
#include <ignition/common/Animation.hh>
#include <ignition/common/graphics/Types.hh>

#include <ignition/msgs/particle_emitter.pb.h>

#include <ignition/rendering/RenderTypes.hh>

#include <ignition/gazebo/config.hh>
Expand Down Expand Up @@ -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.
Expand Down
80 changes: 80 additions & 0 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -63,6 +63,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"
Expand Down Expand Up @@ -166,6 +167,17 @@ class ignition::gazebo::RenderUtilPrivate
public: std::vector<std::tuple<Entity, sdf::Sensor, Entity>>
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<std::tuple<Entity, msgs::ParticleEmitter, Entity>>
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<Entity, msgs::ParticleEmitter>
newParticleEmittersCmds;

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

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

// update pose comp here
if (_emitterCmd->Data().has_pose())
{
auto poseComp = _ecm.Component<components::Pose>(_entity);
if (poseComp)
poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose());
}
_ecm.RemoveComponent<components::ParticleEmitterCmd>(_entity);

return true;
});

// Update lights
auto olderEntitiesLightsCmdToDelete =
std::move(this->dataPtr->entityLightsCmdToDelete);
Expand Down Expand Up @@ -483,6 +516,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 entityLights = std::move(this->dataPtr->entityLights);
Expand All @@ -499,6 +535,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->entityLights.clear();
Expand Down Expand Up @@ -601,6 +639,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)
Expand Down Expand Up @@ -1174,6 +1224,17 @@ void RenderUtilPrivate::CreateRenderingEntities(
return true;
});

// particle emitters
_ecm.Each<components::ParticleEmitter, components::ParentEntity>(
[&](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
Expand Down Expand Up @@ -1385,6 +1446,17 @@ void RenderUtilPrivate::CreateRenderingEntities(
return true;
});

// particle emitters
_ecm.EachNew<components::ParticleEmitter, components::ParentEntity>(
[&](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
Expand Down Expand Up @@ -1626,6 +1698,14 @@ void RenderUtilPrivate::RemoveRenderingEntities(
return true;
});

// particle emitters
_ecm.EachRemoved<components::ParticleEmitter>(
[&](const Entity &_entity, const components::ParticleEmitter *)->bool
{
this->removeEntities[_entity] = _info.iterations;
return true;
});

// cameras
_ecm.EachRemoved<components::Camera>(
[&](const Entity &_entity, const components::Camera *)->bool
Expand Down
Loading

0 comments on commit deddb6f

Please sign in to comment.