@@ -4030,8 +4030,11 @@ GTEST_TEST(StateSelection, FreeBodiesVsFloatingBaseBodies) {
4030
4030
const ModelInstanceIndex table_model =
4031
4031
parser.AddModelsFromUrl (table_sdf_url).at (0 );
4032
4032
const RigidBody<double >& table = plant.GetBodyByName (" link" , table_model);
4033
- plant.AddJoint (std::make_unique<PrismaticJoint<double >>(
4034
- " table" , plant.world_frame (), table.body_frame (), Vector3d (1 , 1 , 1 )));
4033
+ const auto & prismatic_joint =
4034
+ plant.AddJoint (std::make_unique<PrismaticJoint<double >>(
4035
+ " table" , plant.world_frame (), table.body_frame (),
4036
+ Vector3d (1 , 1 , 1 )));
4037
+ EXPECT_FALSE (prismatic_joint.is_ephemeral ());
4035
4038
4036
4039
// Add a mug with no joint. This will become a floating base body at
4037
4040
// finalization unless we add a joint.
@@ -4040,7 +4043,10 @@ GTEST_TEST(StateSelection, FreeBodiesVsFloatingBaseBodies) {
4040
4043
if (!mug_in_world) {
4041
4044
// Explicitly put a 6-dof joint between mug and table, making this a
4042
4045
// "free" body, but _not_ a floating base body.
4043
- plant.AddJoint <QuaternionFloatingJoint>(" sixdof" , table, {}, mug, {});
4046
+ const auto & joint =
4047
+ plant.AddJoint <QuaternionFloatingJoint>(" sixdof" , table, {}, mug, {});
4048
+ // An explicitly added joint is not ephemeral.
4049
+ EXPECT_FALSE (joint.is_ephemeral ());
4044
4050
}
4045
4051
4046
4052
plant.Finalize ();
@@ -4280,6 +4286,7 @@ GTEST_TEST(StateSelection, FloatingBodies) {
4280
4286
// Verify that we can control what kind of joint is used to connect an
4281
4287
// unconnected body to World, globally or per-model instance. The default
4282
4288
// should be QuaternionFloatingJoint, with RpyFloating and Weld as options.
4289
+ // These should all be marked "ephemeral" since they aren't user-added.
4283
4290
//
4284
4291
// We'll also verify that we can set state (q & v), pose, and velocity using the
4285
4292
// generic Joint API applied to the floating joints. We'll also check that we
@@ -4321,9 +4328,10 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
4321
4328
EXPECT_EQ (plant->num_positions (), 14 );
4322
4329
EXPECT_EQ (plant->num_velocities (), 12 );
4323
4330
4324
- // When base joints are added they are named after the base body.
4331
+ // When ephemeral base joints are added they are named after the base body.
4325
4332
const Joint<double >& quaternion_joint =
4326
4333
plant->GetJointByName (" InstanceBody" );
4334
+ EXPECT_TRUE (quaternion_joint.is_ephemeral ());
4327
4335
auto context = plant->CreateDefaultContext ();
4328
4336
Eigen::Vector<double , 7 > set_q;
4329
4337
set_q << 0.1 , 0.2 , 0.3 , 0.4 , 0.5 , 0.6 , 0.7 ;
@@ -4380,6 +4388,7 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
4380
4388
4381
4389
// When base joints are added they are named after the base body.
4382
4390
const Joint<double >& instance_joint = plant->GetJointByName (" InstanceBody" );
4391
+ EXPECT_TRUE (instance_joint.is_ephemeral ());
4383
4392
auto context = plant->CreateDefaultContext ();
4384
4393
Vector6d set_q;
4385
4394
set_q << 0.1 , 0.2 , 0.3 , 0.4 , 0.5 , 0.6 ;
@@ -4445,6 +4454,7 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
4445
4454
// We'll use the weld joint to generate some Joint API errors.
4446
4455
const Joint<double >& weld_joint = plant->GetJointByName (" DefaultBody" );
4447
4456
EXPECT_EQ (weld_joint.type_name (), " weld" );
4457
+ EXPECT_TRUE (weld_joint.is_ephemeral ());
4448
4458
auto context = plant->CreateDefaultContext ();
4449
4459
4450
4460
// SetPositions() and SetVelocities() should work for every joint as
0 commit comments