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

Modifies the dropweight test to test for breaching the surface. #162

Merged
merged 8 commits into from
Mar 2, 2022
Merged
Show file tree
Hide file tree
Changes from 4 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
37 changes: 30 additions & 7 deletions lrauv_ignition_plugins/test/helper/LrauvTestFixture.hh
Original file line number Diff line number Diff line change
Expand Up @@ -50,12 +50,13 @@ double angleDiff(double _a, double _b)
return diff.Radian();
}

/// \brief Convenient fixture that provides boilerplate code common to most
/// LRAUV tests.
class LrauvTestFixture : public ::testing::Test
/// \brief Abstract base class for fixture that provides boilerplate code common
/// to most LRAUV tests.
class LrauvTestFixtureBase : public ::testing::Test
{
// Documentation inherited
protected: void SetUp() override
// Setup the specified world.
// \param[in] _worldName Name of the world to load.
public: void SetUp(const std::string &_worldName)
{
ignition::common::Console::SetVerbosity(4);

Expand All @@ -66,12 +67,12 @@ class LrauvTestFixture : public ::testing::Test
commandTopic);

auto stateTopic = "/tethys/state_topic";
this->node.Subscribe(stateTopic, &LrauvTestFixture::OnState, this);
this->node.Subscribe(stateTopic, &LrauvTestFixtureBase::OnState, this);

// Setup fixture
this->fixture = std::make_unique<ignition::gazebo::TestFixture>(
ignition::common::joinPaths(
std::string(PROJECT_SOURCE_PATH), "worlds", "buoyant_tethys.sdf"));
std::string(PROJECT_SOURCE_PATH), "worlds", _worldName));

fixture->OnPostUpdate(
[&](const ignition::gazebo::UpdateInfo &_info,
Expand Down Expand Up @@ -302,4 +303,26 @@ class LrauvTestFixture : public ::testing::Test
/// \brief Publishes commands
public: ignition::transport::Node::Publisher commandPub;
};


/// \brief Loads the default "buyant_tethys.sdf" world.
class LrauvTestFixture : public LrauvTestFixtureBase
{
/// Documentation inherited
protected: void SetUp() override
{
LrauvTestFixtureBase::SetUp("buoyant_tethys.sdf");
}
};

/// \brief Loads the default "buyant_tethys_At_depth.sdf" world.
/// This world has the robot start at a certain depth.
class LrauvTestFixtureAtDepth : public LrauvTestFixtureBase
{
/// Documentation inherited
protected: void SetUp() override
{
LrauvTestFixtureBase::SetUp("buoyant_tethys_at_depth.sdf");
}
};
#endif
34 changes: 27 additions & 7 deletions lrauv_ignition_plugins/test/test_drop_weight.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,13 +29,23 @@
#include <fstream>

//////////////////////////////////////////////////
TEST_F(LrauvTestFixture, DropWeightRelease)
TEST_F(LrauvTestFixtureAtDepth, DropWeightRelease)
{
// Max iterations
const int maxIterations{3800};

// Surface is at 0m
const double targetZ{0};
// Tolerance, the vehicle will breach the surface
const double tol{0.5};
// Starting point of the vehicle
const double startZ{-10};

// Get initial Z
this->fixture->Server()->Run(true, 100, false);
EXPECT_EQ(100, this->iterations);
EXPECT_EQ(100, this->tethysPoses.size());
EXPECT_NEAR(0.0, this->tethysPoses.back().Pos().Z(), 0.05);
EXPECT_NEAR(startZ, this->tethysPoses.back().Pos().Z(), 0.05);

// Tell the vehicle to release the weight
lrauv_ignition_plugins::msgs::LRAUVCommand cmdMsg;
Expand All @@ -44,16 +54,26 @@ TEST_F(LrauvTestFixture, DropWeightRelease)
// Neutral buoyancy
cmdMsg.set_buoyancyaction_(0.0005);

// Run server until the command is processed and the model floats to a
// certain height
double targetZ{0.005};
// Run the server for fixed iterations
this->PublishCommandWhile(cmdMsg, [&]()
{
return this->tethysPoses.back().Pos().Z() < targetZ;
return this->iterations <= maxIterations;
});

for (auto pose : this->tethysPoses)
{
// Make sure that the vehicle just breaches the surface of the the water
EXPECT_GT(targetZ + tol, pose.Pos().Z());

// MAke sure vehicle goes up.
EXPECT_LT(startZ - tol, pose.Pos().Z());
}

// Actually ran the server.
EXPECT_LT(100, this->iterations);
EXPECT_LT(100, this->tethysPoses.size());
EXPECT_LT(targetZ, this->tethysPoses.back().Pos().Z());

// Make sure we do get near the surface
EXPECT_NEAR(targetZ, this->tethysPoses.back().Pos().Z(), tol);
}

2 changes: 1 addition & 1 deletion lrauv_ignition_plugins/test/test_mass_shifter.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#include <fstream>

//////////////////////////////////////////////////
TEST_F(LrauvTestFixture, MassShifterTilt)
TEST_F(LrauvTestFixtureAtDepth, MassShifterTilt)
{
// Check initial orientation
this->fixture->Server()->Run(true, 100, false);
Expand Down
8 changes: 4 additions & 4 deletions lrauv_ignition_plugins/worlds/buoyant_tethys.sdf
Original file line number Diff line number Diff line change
Expand Up @@ -35,15 +35,15 @@
<plugin
filename="ignition-gazebo-buoyancy-system"
name="ignition::gazebo::systems::Buoyancy">
<!-- TODO: fix behaviour near surface, see https://github.com/osrf/lrauv/issues/102
<!-- TODO: fix behaviour near surface, see https://github.com/osrf/lrauv/issues/102-->
<graded_buoyancy>
<default_density>1025</default_density>
<density_change>
<above_depth>0.5</above_depth>
<density>1</density>
<density>0</density>
</density_change>
</graded_buoyancy-->
<uniform_fluid_density>1025</uniform_fluid_density>
</graded_buoyancy>
<!--<uniform_fluid_density>1025</uniform_fluid_density> -->
</plugin>

<!-- Requires ParticleEmitter2 in ign-gazebo 4.8.0, which will be copied
Expand Down
Loading