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 rotating cubes when placed by GUI tool while using the buoyancy plugin #1064

Merged
merged 5 commits into from
Sep 28, 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
11 changes: 8 additions & 3 deletions src/systems/buoyancy/Buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -324,9 +324,6 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
return true;
}

enableComponent<components::Inertial>(_ecm, _entity);
enableComponent<components::WorldPose>(_ecm, _entity);

Link link(_entity);

std::vector<Entity> collisions = _ecm.ChildrenByComponents(
Expand Down Expand Up @@ -421,6 +418,14 @@ void Buoyancy::PreUpdate(const ignition::gazebo::UpdateInfo &_info,
const components::Volume *_volume,
const components::CenterOfVolume *_centerOfVolume) -> bool
{
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
4 changes: 2 additions & 2 deletions 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 = 1000;
std::size_t iterations = 1001;

bool finished = false;
test::Relay testSystem;
Expand Down Expand Up @@ -183,7 +183,7 @@ TEST_F(BuoyancyTest, UniformWorldMovement)

if (_info.iterations == iterations)
{
EXPECT_NEAR(-1.63, submarineSinkingPose->Data().Pos().Z(), 1e-2);
EXPECT_NEAR(-1.64, submarineSinkingPose->Data().Pos().Z(), 1e-2);
EXPECT_NEAR(4.90, submarineBuoyantPose->Data().Pos().Z(), 1e-2);
EXPECT_NEAR(171.4, duckPose->Data().Pos().Z(), 1e-2);
finished = true;
Expand Down