Skip to content

Commit

Permalink
4 to 5
Browse files Browse the repository at this point in the history
Signed-off-by: Louise Poubel <[email protected]>
  • Loading branch information
chapulina committed Mar 4, 2021
2 parents 6c91ff9 + 86e6ad9 commit 4e692db
Show file tree
Hide file tree
Showing 19 changed files with 1,201 additions and 689 deletions.
48 changes: 48 additions & 0 deletions Changelog.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,53 @@
## Ignition Gazebo 4.x

### Ignition Gazebo 4.6.0 (2021-03-01)

1. Use a custom data structure to manage entity feature maps.
* [Pull Request 586](https://github.com/ignitionrobotics/ign-gazebo/pull/586)

1. Limit scene broadcast publications when paused.
* [Pull Request 497](https://github.com/ignitionrobotics/ign-gazebo/pull/497)

1. Report performer count in PerformerDetector plugin.
* [Pull Request 652](https://github.com/ignitionrobotics/ign-gazebo/pull/652)

1. Cache top level and static to speed up physics system.
* [Pull Request 656](https://github.com/ignitionrobotics/ign-gazebo/pull/656)

1. Support particle emitter modification using partial message.
* [Pull Request 651](https://github.com/ignitionrobotics/ign-gazebo/pull/651)

1. Set LD_LIBRARY_PATH on Actions CI.
* [Pull Request 650](https://github.com/ignitionrobotics/ign-gazebo/pull/650)

1. Fix flaky SceneBroadcaster test.
* [Pull Request 641](https://github.com/ignitionrobotics/ign-gazebo/pull/641)

1. Add a convenience function for getting possibly non-existing components.
* [Pull Request 629](https://github.com/ignitionrobotics/ign-gazebo/pull/629)

1. Add msg to show the computed temperature range computed from temperature
gradient.
* [Pull Request 643](https://github.com/ignitionrobotics/ign-gazebo/pull/643)

1. Add TF/Pose_V pub in DiffDrive.
* [Pull Request 548](https://github.com/ignitionrobotics/ign-gazebo/pull/548)

1. Relax flaky performance test.
* [Pull Request 640](https://github.com/ignitionrobotics/ign-gazebo/pull/640)

1. Improve velocity control test.
* [Pull Request 642](https://github.com/ignitionrobotics/ign-gazebo/pull/642)

1. Validity check for user defined topics in JointPositionController.
* [Pull Request 639](https://github.com/ignitionrobotics/ign-gazebo/pull/639)

1. Add laser_retro support.
* [Pull Request 603](https://github.com/ignitionrobotics/ign-gazebo/pull/603)

1. Fix pose of plane visual with non-default normal vector.
* [Pull Request 574](https://github.com/ignitionrobotics/ign-gazebo/pull/574)

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

1. Added particle system.
Expand Down
3 changes: 3 additions & 0 deletions include/ignition/gazebo/gui/GuiRunner.hh
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,9 @@ class IGNITION_GAZEBO_GUI_VISIBLE GuiRunner : public QObject
public: explicit IGN_DEPRECATED(5.0) GuiRunner(
const std::string &_worldName);

/// \brief Destructor
public: ~GuiRunner() override;

/// \brief Callback when a plugin has been added.
/// \param[in] _objectName Plugin's object name.
public slots: void OnPluginAdded(const QString &_objectName);
Expand Down
52 changes: 47 additions & 5 deletions src/gui/GuiRunner.cc
Original file line number Diff line number Diff line change
Expand Up @@ -35,6 +35,9 @@ using namespace gazebo;
/////////////////////////////////////////////////
class ignition::gazebo::GuiRunner::Implementation
{
/// \brief Update the plugins.
public: void UpdatePlugins();

/// \brief Entity-component manager.
public: gazebo::EntityComponentManager ecm;

Expand All @@ -46,6 +49,15 @@ class ignition::gazebo::GuiRunner::Implementation

/// \brief Latest update info
public: UpdateInfo updateInfo;

/// \brief Flag used to end the updateThread.
public: bool running{false};

/// \brief Mutex to protect the plugin update.
public: std::mutex updateMutex;

/// \brief The plugin update thread..
public: std::thread updateThread;
};

/////////////////////////////////////////////////
Expand Down Expand Up @@ -77,6 +89,30 @@ GuiRunner::GuiRunner(const std::string &_worldName)
<< "]..." << std::endl;

this->RequestState();

// Periodically update the plugins
// \todo(anyone) Move the global variables to GuiRunner::Implementation on v5
this->dataPtr->running = true;
this->dataPtr->updateThread = std::thread([&]()
{
while (this->dataPtr->running)
{
{
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
this->dataPtr->UpdatePlugins();
}
// This is roughly a 30Hz update rate.
std::this_thread::sleep_for(std::chrono::milliseconds(33));
}
});
}

/////////////////////////////////////////////////
GuiRunner::~GuiRunner()
{
this->dataPtr->running = false;
if (this->dataPtr->updateThread.joinable())
this->dataPtr->updateThread.join();
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -153,17 +189,23 @@ void GuiRunner::OnState(const msgs::SerializedStepMap &_msg)
IGN_PROFILE_THREAD_NAME("GuiRunner::OnState");
IGN_PROFILE("GuiRunner::Update");

std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);
this->dataPtr->ecm.SetState(_msg.state());

// Update all plugins
this->dataPtr->updateInfo = convert<UpdateInfo>(_msg.stats());
this->dataPtr->UpdatePlugins();
this->dataPtr->ecm.ClearNewlyCreatedEntities();
this->dataPtr->ecm.ProcessRemoveEntityRequests();
}

/////////////////////////////////////////////////
void GuiRunner::Implementation::UpdatePlugins()
{
auto plugins = gui::App()->findChildren<GuiSystem *>();
for (auto plugin : plugins)
{
plugin->Update(this->dataPtr->updateInfo, this->dataPtr->ecm);
plugin->Update(this->updateInfo, this->ecm);
}
this->dataPtr->ecm.ClearNewlyCreatedEntities();
this->dataPtr->ecm.ProcessRemoveEntityRequests();
this->dataPtr->ecm.ClearRemovedComponents();
this->ecm.ClearRemovedComponents();
}

15 changes: 13 additions & 2 deletions src/rendering/RenderUtil.cc
Original file line number Diff line number Diff line change
Expand Up @@ -185,6 +185,9 @@ class ignition::gazebo::RenderUtilPrivate
public: std::unordered_map<Entity, msgs::ParticleEmitter>
newParticleEmittersCmds;

/// \brief A list of entities with particle emitter cmds to remove
public: std::vector<Entity> particleCmdsToRemove;

/// \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 @@ -348,14 +351,21 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/,
{
std::lock_guard<std::mutex> lock(this->dataPtr->updateMutex);

// Remove the commands from the entity
// these are commands from the last iteration. We want to make sure all
// systems have a chance to process them first before they are removed.
for (const auto &entity : this->dataPtr->particleCmdsToRemove)
_ecm.RemoveComponent<components::ParticleEmitterCmd>(entity);
this->dataPtr->particleCmdsToRemove.clear();

// 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();
_emitterCmd->Data();

// update pose comp here
if (_emitterCmd->Data().has_pose())
Expand All @@ -364,7 +374,8 @@ void RenderUtil::UpdateECM(const UpdateInfo &/*_info*/,
if (poseComp)
poseComp->Data() = msgs::Convert(_emitterCmd->Data().pose());
}
_ecm.RemoveComponent<components::ParticleEmitterCmd>(_entity);
// Store the entity ids to clear outside of the `Each` loop.
this->dataPtr->particleCmdsToRemove.push_back(_entity);

return true;
});
Expand Down
36 changes: 25 additions & 11 deletions src/rendering/SceneManager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1211,7 +1211,7 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}
default:
{
emitter->SetType(ignition::rendering::EmitterType::EM_POINT);
// Do nothing if type is not set.
}
}

Expand All @@ -1220,20 +1220,28 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
emitter->SetEmitterSize(ignition::msgs::Convert(_emitter.size()));

// Rate.
emitter->SetRate(_emitter.rate());
if (_emitter.has_rate())
emitter->SetRate(_emitter.rate().data());

// Duration.
emitter->SetDuration(_emitter.duration());
if (_emitter.has_duration())
emitter->SetDuration(_emitter.duration().data());

// Emitting.
emitter->SetEmitting(_emitter.emitting());
if (_emitter.has_emitting()) {
emitter->SetEmitting(_emitter.emitting().data());
}

// Particle size.
emitter->SetParticleSize(
ignition::msgs::Convert(_emitter.particle_size()));
if (_emitter.has_particle_size())
{
emitter->SetParticleSize(
ignition::msgs::Convert(_emitter.particle_size()));
}

// Lifetime.
emitter->SetLifetime(_emitter.lifetime());
if (_emitter.has_lifetime())
emitter->SetLifetime(_emitter.lifetime().data());

// Material.
if (_emitter.has_material())
Expand All @@ -1244,12 +1252,17 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}

// Velocity range.
emitter->SetVelocityRange(_emitter.min_velocity(), _emitter.max_velocity());
if (_emitter.has_min_velocity() && _emitter.has_max_velocity())
{
emitter->SetVelocityRange(_emitter.min_velocity().data(),
_emitter.max_velocity().data());
}

// Color range image.
if (!_emitter.color_range_image().empty())
if (_emitter.has_color_range_image() &&
!_emitter.color_range_image().data().empty())
{
emitter->SetColorRangeImage(_emitter.color_range_image());
emitter->SetColorRangeImage(_emitter.color_range_image().data());
}
// Color range.
else if (_emitter.has_color_start() && _emitter.has_color_end())
Expand All @@ -1260,7 +1273,8 @@ rendering::ParticleEmitterPtr SceneManager::UpdateParticleEmitter(Entity _id,
}

// Scale rate.
emitter->SetScaleRate(_emitter.scale_rate());
if (_emitter.has_scale_rate())
emitter->SetScaleRate(_emitter.scale_rate().data());

// pose
if (_emitter.has_pose())
Expand Down
21 changes: 13 additions & 8 deletions src/systems/particle_emitter/ParticleEmitter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -188,13 +188,16 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_size(), size);

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

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

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

// Particle size.
size = ignition::math::Vector3d::One;
Expand All @@ -203,7 +206,8 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_particle_size(), size);

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

// Material.
if (_sdf->HasElement("material"))
Expand All @@ -216,11 +220,11 @@ void ParticleEmitter::Configure(const Entity &_entity,
}

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

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

// Color start.
Expand All @@ -236,7 +240,7 @@ void ParticleEmitter::Configure(const Entity &_entity,
ignition::msgs::Set(this->dataPtr->emitter.mutable_color_end(), color);

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

// Color range image.
Expand All @@ -250,7 +254,8 @@ void ParticleEmitter::Configure(const Entity &_entity,
systemPaths.SetFilePathEnv(kResourcePathEnv);
auto absolutePath = systemPaths.FindFile(path);

this->dataPtr->emitter.set_color_range_image(absolutePath);
this->dataPtr->emitter.mutable_color_range_image()->set_data(
absolutePath);
}

igndbg << "Loading particle emitter:" << std::endl
Expand Down
5 changes: 5 additions & 0 deletions src/systems/performer_detector/PerformerDetector.cc
Original file line number Diff line number Diff line change
Expand Up @@ -242,6 +242,11 @@ void PerformerDetector::Publish(
headerData->set_key("state");
headerData->add_value(std::to_string(_state));
}
{
auto *headerData = msg.mutable_header()->add_data();
headerData->set_key("count");
headerData->add_value(std::to_string(this->detectedEntities.size()));
}

// Include the optional extra header data.
for (const auto &data : this->extraHeaderData)
Expand Down
4 changes: 3 additions & 1 deletion src/systems/performer_detector/PerformerDetector.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,9 @@ namespace systems
/// header will contain the key "frame_id" with a value set to the name of
/// the model containing the PerformerDetector system and the key "state" with
/// a value set to "1" if the performer is entering the detector's region and
/// "0" if the performer is leaving the region.
/// "0" if the performer is leaving the region. The `data` field of the
/// header will also contain the key "count" with a value set to the
/// number of performers currently in the region.
///
/// The PerformerDetector has to be attached to a <model> and it's region is
/// centered on the containing model's origin.
Expand Down
10 changes: 10 additions & 0 deletions src/systems/physics/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -7,3 +7,13 @@ gz_add_system(physics
ignition-physics${IGN_PHYSICS_VER}::ignition-physics${IGN_PHYSICS_VER}
)

set (gtest_sources
EntityFeatureMap_TEST.cc
)

ign_build_tests(TYPE UNIT
SOURCES
${gtest_sources}
LIB_DEPS
ignition-physics${IGN_PHYSICS_VER}::core
)
Loading

0 comments on commit 4e692db

Please sign in to comment.