Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Fix WindEffects Plugin bug, not configuring new links #844

Merged
merged 3 commits into from
Jun 17, 2021
Merged
Show file tree
Hide file tree
Changes from all 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
66 changes: 28 additions & 38 deletions src/systems/wind_effects/WindEffects.cc
Original file line number Diff line number Diff line change
Expand Up @@ -152,10 +152,6 @@ class ignition::gazebo::systems::WindEffectsPrivate
/// valid.
public: bool validConfig{false};

/// \brief Whether links have been initialized. Initialization involves
/// creating components this system needs on links that are affected by wind.
public: bool linksInitialized{false};

/// \brief Mutex to protect currWindVelSeed and windEnabled
public: std::mutex windInfoMutex;

Expand Down Expand Up @@ -542,45 +538,39 @@ void WindEffects::PreUpdate(const UpdateInfo &_info,
// Process commands
this->dataPtr->ProcessCommandQueue(_ecm);

if (this->dataPtr->validConfig)
if (!this->dataPtr->validConfig)
return;

_ecm.EachNew<components::Link, components::WindMode>(
[&](const Entity &_entity, components::Link *,
components::WindMode *_windMode) -> bool
{
if (!this->dataPtr->linksInitialized)
if (_windMode->Data())
{
_ecm.Each<components::Link, components::WindMode>(
[&](const Entity &_entity, components::Link *,
components::WindMode *_windMode) -> bool
{
if (_windMode->Data())
{
// Create a WorldLinearVelocity component on the link so that
// physics can populate it
if (!_ecm.Component<components::WorldLinearVelocity>(_entity))
{
_ecm.CreateComponent(_entity,
components::WorldLinearVelocity());
}
if (!_ecm.Component<components::WorldPose>(_entity))
{
_ecm.CreateComponent(_entity, components::WorldPose());
}
}
return true;
});

this->dataPtr->linksInitialized = true;
// Create a WorldLinearVelocity component on the link so that
// physics can populate it
if (!_ecm.Component<components::WorldLinearVelocity>(_entity))
{
_ecm.CreateComponent(_entity,
components::WorldLinearVelocity());
}
if (!_ecm.Component<components::WorldPose>(_entity))
{
_ecm.CreateComponent(_entity, components::WorldPose());
}
}
else
{
if (_info.paused)
return;
return true;
});

if (!this->dataPtr->currentWindInfo.enable_wind())
return;
if (_info.paused)
return;

if (!this->dataPtr->currentWindInfo.enable_wind())
return;

this->dataPtr->UpdateWindVelocity(_info, _ecm);
this->dataPtr->ApplyWindForce(_info, _ecm);

this->dataPtr->UpdateWindVelocity(_info, _ecm);
this->dataPtr->ApplyWindForce(_info, _ecm);
}
}
}

IGNITION_ADD_PLUGIN(WindEffects, System,
Expand Down
52 changes: 52 additions & 0 deletions test/integration/wind_effects.cc
Original file line number Diff line number Diff line change
Expand Up @@ -326,3 +326,55 @@ TEST_F(WindEffectsTest , TopicsAndServices)
lastVelMagnitude = velMagnitude;
}
}

/// Test if adding a link with wind after first iteration adds
/// WorldLinearVelocity component properly
TEST_F(WindEffectsTest, WindEntityAddedAfterStart)
{
const std::string windBox = R"EOF(
<?xml version="1.0" ?>
<sdf version="1.6">
<model name="box_wind">
<pose>5 5 5 0 0 0</pose>
<enable_wind>true</enable_wind>
<link name="test_link_wind">
<collision name="collision">
<geometry>
<box>
<size>1 1 1</size>
</box>
</geometry>
</collision>
</link>
</model>
</sdf>)EOF";

this->StartServer("/test/worlds/wind_effects.sdf");

LinkComponentRecorder<components::WorldLinearVelocity>
linkVelocityComponent("test_link_wind");
this->server->AddSystem(linkVelocityComponent.systemPtr);
EXPECT_TRUE(linkVelocityComponent.values.empty());

// Run the logger for a time, check it is still empty
this->server->Run(true, 10, false);
EXPECT_TRUE(linkVelocityComponent.values.empty());

// Add the box to be logged via the command system
// and check that is not empty
transport::Node node;
msgs::EntityFactory req;
unsigned int timeout = 5000;
std::string service{"/world/wind_demo/create"};
msgs::Boolean res;
bool result;

req.set_sdf(windBox);
EXPECT_TRUE(node.Request(service, req, timeout, res, result));
EXPECT_TRUE(result);
EXPECT_TRUE(res.data());

// Now box_wind WorldLinearVelocity component should be added
this->server->Run(true, 10, false);
ASSERT_FALSE(linkVelocityComponent.values.empty());
}
4 changes: 4 additions & 0 deletions test/worlds/wind_effects.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
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-wind-effects-system"
Expand Down