Skip to content

Fix buoyancy not being applied for one iteration #1211

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

Merged
merged 5 commits into from
Nov 30, 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
23 changes: 13 additions & 10 deletions src/systems/buoyancy/Buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -441,11 +441,6 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
{
auto newPose = enableComponent<components::Inertial>(_ecm, _entity);
newPose |= enableComponent<components::WorldPose>(_ecm, _entity);
if (newPose)
{
// Skip entity if WorldPose and inertial are not yet ready
return true;
}

// World pose of the link.
math::Pose3d linkWorldPose = worldPose(_entity, _ecm);
Expand Down Expand Up @@ -477,6 +472,13 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
else if (this->dataPtr->buoyancyType
== BuoyancyPrivate::BuoyancyType::GRADED_BUOYANCY)
{
if (newPose)
{
// Skip entity if WorldPose and inertial are not yet ready
// TODO(arjo): Find a way of disabling gravity effects for
// this first iteration.
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think we may be able to avoid this skip if we use gazebo::worldPose instead of the WorldPose component. That function should provide the world pose straight away.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Hmm, but we need to use link::WorldInertialPose...

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ahh I see, maybe the implementation of that method can be improved 🤔

return true;
}
std::vector<Entity> collisions = _ecm.ChildrenByComponents(
_entity, components::Collision());
this->dataPtr->buoyancyForces.clear();
Expand Down Expand Up @@ -521,12 +523,13 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
}
}
}
}
auto [force, torque] = this->dataPtr->ResolveForces(
auto [force, torque] = this->dataPtr->ResolveForces(
link.WorldInertialPose(_ecm).value());
// Apply the wrench to the link. This wrench is applied in the
// Physics System.
link.AddWorldWrench(_ecm, force, torque);
// Apply the wrench to the link. This wrench is applied in the
// Physics System.
link.AddWorldWrench(_ecm, force, torque);
}

return true;
});
}
Expand Down
2 changes: 1 addition & 1 deletion test/integration/buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ TEST_F(BuoyancyTest, UniformWorldMovement)
using namespace std::chrono_literals;
server.SetUpdatePeriod(1ns);

std::size_t iterations = 1001;
std::size_t iterations = 1000;

bool finished = false;
test::Relay testSystem;
Expand Down