Skip to content

Commit

Permalink
Don't put NaN inertias in tests.
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 committed Jan 15, 2025
1 parent ed9ae14 commit e7c3d87
Show file tree
Hide file tree
Showing 5 changed files with 10 additions and 10 deletions.
2 changes: 1 addition & 1 deletion multibody/tree/rotational_inertia.h
Original file line number Diff line number Diff line change
Expand Up @@ -190,7 +190,7 @@ class RotationalInertia {
RotationalInertia(const T& Ixx, const T& Iyy, const T& Izz, const T& Ixy,
const T& Ixz, const T& Iyz) {
set_moments_and_products_no_validity_check(Ixx, Iyy, Izz, Ixy, Ixz, Iyz);
// DRAKE_ASSERT_VOID(ThrowIfNotPhysicallyValid(__func__));
DRAKE_ASSERT_VOID(ThrowIfNotPhysicallyValid(__func__));
}

/// Constructs a rotational inertia for a particle Q of mass `mass`, whose
Expand Down
6 changes: 3 additions & 3 deletions multibody/tree/test/frames_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,11 +39,11 @@ const double kEpsilon = std::numeric_limits<double>::epsilon();
class FrameTests : public ::testing::Test {
public:
void SetUp() override {
// Creates a NaN SpatialInertia to instantiate a body for the test.
// Using a NaN spatial inertia is ok in this unit test since all
// Creates a Zero SpatialInertia to instantiate a body for the test.
// Using a Zero spatial inertia is ok in this unit test since all
// computations only relate to frame kinematics (and therefore mass
// properties do not play any role.)
const auto M_Bo_B = SpatialInertia<double>::NaN();
const auto M_Bo_B = SpatialInertia<double>::Zero();

// Create an empty model.
auto model = std::make_unique<internal::MultibodyTree<double>>();
Expand Down
2 changes: 1 addition & 1 deletion multibody/tree/test/multibody_tree_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1261,7 +1261,7 @@ class WeldMobilizerTest : public ::testing::Test {
void SetUp() override {
// Spatial inertia for each body. The actual value is not important for
// these tests since they are all kinematic.
const auto M_B = SpatialInertia<double>::NaN();
const auto M_B = SpatialInertia<double>::Zero();

// Create an empty model.
auto model = std::make_unique<MultibodyTree<double>>();
Expand Down
4 changes: 2 additions & 2 deletions multibody/tree/test/prismatic_spring_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,8 +29,8 @@ class SpringTester : public ::testing::Test {
// Create an empty model.
auto model = std::make_unique<MultibodyTree<double>>();

bodyA_ = &model->AddRigidBody("BodyA", SpatialInertia<double>::NaN());
bodyB_ = &model->AddRigidBody("BodyB", SpatialInertia<double>::NaN());
bodyA_ = &model->AddRigidBody("BodyA", SpatialInertia<double>::Zero());
bodyB_ = &model->AddRigidBody("BodyB", SpatialInertia<double>::Zero());

model->AddJoint<WeldJoint>("WeldBodyAToWorld", model->world_body(), {},
*bodyA_, {},
Expand Down
6 changes: 3 additions & 3 deletions multibody/tree/test/revolute_spring_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,9 +30,9 @@ class SpringTester : public ::testing::Test {
// Create an empty model.
auto model = std::make_unique<MultibodyTree<double>>();

bodyA_ = &model->AddRigidBody("BodyA", SpatialInertia<double>::NaN());
bodyB_ = &model->AddRigidBody("BodyB", SpatialInertia<double>::NaN());
bodyC_ = &model->AddRigidBody("BodyC", SpatialInertia<double>::NaN());
bodyA_ = &model->AddRigidBody("BodyA", SpatialInertia<double>::Zero());
bodyB_ = &model->AddRigidBody("BodyB", SpatialInertia<double>::Zero());
bodyC_ = &model->AddRigidBody("BodyC", SpatialInertia<double>::Zero());

model->AddJoint<WeldJoint>("WeldBodyAToWorld", model->world_body(), {},
*bodyA_, {},
Expand Down

0 comments on commit e7c3d87

Please sign in to comment.