Skip to content

Commit

Permalink
add test
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Jan 12, 2022
1 parent fe3a501 commit 73afcaf
Showing 1 changed file with 12 additions and 1 deletion.
13 changes: 12 additions & 1 deletion test/integration/link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@
#include <ignition/common/Console.hh>
#include <ignition/common/Util.hh>

#include <ignition/gazebo/components/AngularAcceleration.hh>
#include <ignition/gazebo/components/AngularVelocity.hh>
#include <ignition/gazebo/components/CanonicalLink.hh>
#include <ignition/gazebo/components/Collision.hh>
Expand Down Expand Up @@ -314,23 +315,33 @@ TEST_F(LinkIntegrationTest, LinkAccelerations)

// Before we enable acceleration, acceleration should return nullopt
EXPECT_EQ(std::nullopt, link.WorldLinearAcceleration(ecm));
EXPECT_EQ(std::nullopt, link.WorldAngularAcceleration(ecm));

// After enabling, they should return default values
link.EnableAccelerationChecks(ecm);
EXPECT_EQ(math::Vector3d::Zero, link.WorldLinearAcceleration(ecm));
EXPECT_EQ(math::Vector3d::Zero, link.WorldAngularAcceleration(ecm));
EXPECT_NE(nullptr, ecm.Component<components::WorldLinearAcceleration>(eLink));
EXPECT_NE(nullptr,
ecm.Component<components::WorldAngularAcceleration>(eLink));

// After setting acceleration, we get the value
math::Vector3d linAccel{1.0, 0.0, 0.0};
ecm.SetComponentData<components::WorldLinearAcceleration>(eLink, linAccel);

EXPECT_EQ(linAccel, link.WorldLinearAcceleration(ecm));

math::Vector3d angAccel{0.0, 1.0, 0.0};
ecm.SetComponentData<components::WorldAngularAcceleration>(eLink, angAccel);
EXPECT_EQ(angAccel, link.WorldAngularAcceleration(ecm));

// Disabling accelerations goes back to nullopt
link.EnableAccelerationChecks(ecm, false);

EXPECT_EQ(std::nullopt, link.WorldLinearAcceleration(ecm));
EXPECT_EQ(std::nullopt, link.WorldAngularAcceleration(ecm));
EXPECT_EQ(nullptr, ecm.Component<components::WorldLinearAcceleration>(eLink));
EXPECT_EQ(nullptr,
ecm.Component<components::WorldAngularAcceleration>(eLink));
}

//////////////////////////////////////////////////
Expand Down

0 comments on commit 73afcaf

Please sign in to comment.