Skip to content

Logs a warning if a buoyancy mode is not clearly specified. #1307

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 3 commits into from
Feb 17, 2022
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
8 changes: 8 additions & 0 deletions src/systems/buoyancy/Buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -316,6 +316,14 @@ void Buoyancy::Configure(const Entity &_entity,
argument = argument->GetNextElement();
}
}
else
{
ignwarn <<
"Neither <graded_buoyancy> nor <uniform_fluid_density> specified"
<< std::endl
<< "\tDefaulting to <uniform_fluid_density>1000</uniform_fluid_density>"
<< std::endl;
}

if (_sdf->HasElement("enable"))
{
Expand Down
56 changes: 56 additions & 0 deletions test/integration/buoyancy.cc
Original file line number Diff line number Diff line change
Expand Up @@ -400,6 +400,62 @@ TEST_F(BuoyancyTest, IGN_UTILS_TEST_DISABLED_ON_WIN32(GradedBuoyancy))
EXPECT_TRUE(finished);
}


/////////////////////////////////////////////////
TEST_F(BuoyancyTest, OffsetAndRotationGraded)
{
TestFixture fixture(common::joinPaths(std::string(PROJECT_SOURCE_PATH),
"test", "worlds", "center_of_volume_graded.sdf"));

std::size_t iterations{0};
fixture.OnPostUpdate([&](
const gazebo::UpdateInfo &,
const gazebo::EntityComponentManager &_ecm)
{
// Get links
auto noOffsets = entitiesFromScopedName("no_offset::link", _ecm);
ASSERT_EQ(1u, noOffsets.size());
auto noOffset = *noOffsets.begin();
EXPECT_NE(kNullEntity, noOffset);

auto noOffsetRotateds = entitiesFromScopedName("no_offset_rotated::link",
_ecm);
ASSERT_EQ(1u, noOffsetRotateds.size());
auto noOffsetRotated = *noOffsetRotateds.begin();
EXPECT_NE(kNullEntity, noOffsetRotated);

auto withOffsets = entitiesFromScopedName("com_cov_offset::link", _ecm);
ASSERT_EQ(1u, withOffsets.size());
auto withOffset = *withOffsets.begin();
EXPECT_NE(kNullEntity, withOffset);

auto withOffsetRotateds = entitiesFromScopedName(
"com_cov_offset_rotated::link", _ecm);
ASSERT_EQ(1u, withOffsetRotateds.size());
auto withOffsetRotated = *withOffsetRotateds.begin();
EXPECT_NE(kNullEntity, withOffsetRotated);

// Check that all objects are neutrally buoyant and stay still
auto noOffsetPose = worldPose(noOffset, _ecm);
EXPECT_EQ(math::Pose3d(), noOffsetPose);

auto noOffsetRotatedPose = worldPose(noOffsetRotated, _ecm);
EXPECT_EQ(math::Pose3d(-3, 0, 0, 0.1, 0.2, 0.3), noOffsetRotatedPose);

auto withOffsetPose = worldPose(withOffset, _ecm);
EXPECT_EQ(math::Pose3d(0, 3, 0, 0, 0, 0), withOffsetPose);

auto withOffsetRotatedPose = worldPose(withOffsetRotated, _ecm);
EXPECT_EQ(math::Pose3d(-3, 3, 0, 0.1, 0.2, 0.3), withOffsetRotatedPose);

iterations++;
}).Finalize();

std::size_t targetIterations{1000};
fixture.Server()->Run(true, targetIterations, false);
EXPECT_EQ(targetIterations, iterations);
}

/////////////////////////////////////////////////
TEST_F(BuoyancyTest, OffsetAndRotation)
{
Expand Down
173 changes: 173 additions & 0 deletions test/worlds/center_of_volume_graded.sdf
Original file line number Diff line number Diff line change
@@ -0,0 +1,173 @@
<?xml version="1.0" ?>
<sdf version="1.6">
<world name="center_of_volume">

<physics name="fast" type="ignored">
<real_time_factor>0</real_time_factor>
</physics>
<plugin
filename="libignition-gazebo-physics-system.so"
name="ignition::gazebo::systems::Physics">
</plugin>
<plugin
filename="libignition-gazebo-buoyancy-system.so"
name="ignition::gazebo::systems::Buoyancy">
<graded_buoyancy>
<default_density>1000</default_density>
<density_change>
<above_depth>500</above_depth>
<density>1</density>
</density_change>
</graded_buoyancy>
</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>
<model name='no_offset'>
<pose>0 0 0 0 0 0</pose>
<link name='link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>166.66</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>166.66</iyy>
<iyz>0</iyz>
<izz>166.66</izz>
</inertia>
<mass>1000.0</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</collision>
</link>
</model>

<model name='no_offset_rotated'>
<pose>-3 0 0 0.1 0.2 0.3</pose>
<link name='link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>0 0 0 0 0 0</pose>
<inertia>
<ixx>166.66</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>166.66</iyy>
<iyz>0</iyz>
<izz>166.66</izz>
</inertia>
<mass>1000.0</mass>
</inertial>
<visual name='visual'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<pose>0 0 0 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</collision>
</link>
</model>

<model name='com_cov_offset'>
<pose>0 3 0 0 0 0</pose>
<link name='link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>1 1 1 0 0 0</pose>
<inertia>
<ixx>166.66</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>166.66</iyy>
<iyz>0</iyz>
<izz>166.66</izz>
</inertia>
<mass>1000.0</mass>
</inertial>
<visual name='visual'>
<pose>1 1 1 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<pose>1 1 1 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</collision>
</link>
</model>

<model name='com_cov_offset_rotated'>
<pose>-3 3 0 0.1 0.2 0.3</pose>
<link name='link'>
<pose>0 0 0 0 0 0</pose>
<inertial>
<pose>1 1 1 0 0 0</pose>
<inertia>
<ixx>166.66</ixx>
<ixy>0</ixy>
<ixz>0</ixz>
<iyy>166.66</iyy>
<iyz>0</iyz>
<izz>166.66</izz>
</inertia>
<mass>1000.0</mass>
</inertial>
<visual name='visual'>
<pose>1 1 1 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</visual>
<collision name='collision'>
<pose>1 1 1 0 0 0</pose>
<geometry>
<box>
<size>1.0 1.0 1.0</size>
</box>
</geometry>
</collision>
</link>
</model>

</world>
</sdf>