Skip to content

Commit 753daa3

Browse files
committed
Unambiguously identify ephemeral elements.
1 parent d4f8f16 commit 753daa3

13 files changed

+86
-20
lines changed

bindings/pydrake/multibody/test/plant_test.py

+1
Original file line numberDiff line numberDiff line change
@@ -580,6 +580,7 @@ def _test_multibody_tree_element_mixin(self, T, element):
580580
cls = type(element)
581581
self.assertIsInstance(element.index(), get_index_class(cls, T))
582582
self.assertIsInstance(element.model_instance(), ModelInstanceIndex)
583+
self.assertFalse(element.is_ephemeral())
583584
element.GetParentPlant()
584585

585586
def _test_frame_api(self, T, frame):

bindings/pydrake/multibody/tree_py.cc

+1
Original file line numberDiff line numberDiff line change
@@ -76,6 +76,7 @@ void BindMultibodyElementMixin(PyClass* pcls) {
7676
cls // BR
7777
.def("index", &Class::index)
7878
.def("model_instance", &Class::model_instance)
79+
.def("is_ephemeral", &Class::is_ephemeral)
7980
.def("GetParentPlant",
8081
[](const Class& self) -> const multibody::MultibodyPlant<T>& {
8182
return self.GetParentPlant();

multibody/plant/test/multibody_plant_test.cc

+14-4
Original file line numberDiff line numberDiff line change
@@ -4030,8 +4030,11 @@ GTEST_TEST(StateSelection, FreeBodiesVsFloatingBaseBodies) {
40304030
const ModelInstanceIndex table_model =
40314031
parser.AddModelsFromUrl(table_sdf_url).at(0);
40324032
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());
40354038

40364039
// Add a mug with no joint. This will become a floating base body at
40374040
// finalization unless we add a joint.
@@ -4040,7 +4043,10 @@ GTEST_TEST(StateSelection, FreeBodiesVsFloatingBaseBodies) {
40404043
if (!mug_in_world) {
40414044
// Explicitly put a 6-dof joint between mug and table, making this a
40424045
// "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());
40444050
}
40454051

40464052
plant.Finalize();
@@ -4280,6 +4286,7 @@ GTEST_TEST(StateSelection, FloatingBodies) {
42804286
// Verify that we can control what kind of joint is used to connect an
42814287
// unconnected body to World, globally or per-model instance. The default
42824288
// should be QuaternionFloatingJoint, with RpyFloating and Weld as options.
4289+
// These should all be marked "ephemeral" since they aren't user-added.
42834290
//
42844291
// We'll also verify that we can set state (q & v), pose, and velocity using the
42854292
// generic Joint API applied to the floating joints. We'll also check that we
@@ -4321,9 +4328,10 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
43214328
EXPECT_EQ(plant->num_positions(), 14);
43224329
EXPECT_EQ(plant->num_velocities(), 12);
43234330

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.
43254332
const Joint<double>& quaternion_joint =
43264333
plant->GetJointByName("InstanceBody");
4334+
EXPECT_TRUE(quaternion_joint.is_ephemeral());
43274335
auto context = plant->CreateDefaultContext();
43284336
Eigen::Vector<double, 7> set_q;
43294337
set_q << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6, 0.7;
@@ -4380,6 +4388,7 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
43804388

43814389
// When base joints are added they are named after the base body.
43824390
const Joint<double>& instance_joint = plant->GetJointByName("InstanceBody");
4391+
EXPECT_TRUE(instance_joint.is_ephemeral());
43834392
auto context = plant->CreateDefaultContext();
43844393
Vector6d set_q;
43854394
set_q << 0.1, 0.2, 0.3, 0.4, 0.5, 0.6;
@@ -4445,6 +4454,7 @@ GTEST_TEST(MultibodyPlantTest, BaseBodyJointChoice) {
44454454
// We'll use the weld joint to generate some Joint API errors.
44464455
const Joint<double>& weld_joint = plant->GetJointByName("DefaultBody");
44474456
EXPECT_EQ(weld_joint.type_name(), "weld");
4457+
EXPECT_TRUE(weld_joint.is_ephemeral());
44484458
auto context = plant->CreateDefaultContext();
44494459

44504460
// SetPositions() and SetVelocities() should work for every joint as

multibody/tree/body_node.h

+1
Original file line numberDiff line numberDiff line change
@@ -100,6 +100,7 @@ class BodyNode : public MultibodyElement<T> {
100100
body_(body),
101101
mobilizer_(mobilizer) {
102102
DRAKE_DEMAND(!(parent_node == nullptr && body->index() != world_index()));
103+
this->set_is_ephemeral(true); // BodyNodes are never added by users.
103104
}
104105

105106
~BodyNode() override;

multibody/tree/fixed_offset_frame.cc

+7-3
Original file line numberDiff line numberDiff line change
@@ -53,8 +53,10 @@ std::unique_ptr<Frame<ToScalar>> FixedOffsetFrame<T>::TemplatedDoCloneToScalar(
5353
const internal::MultibodyTree<ToScalar>& tree_clone) const {
5454
const Frame<ToScalar>& parent_frame_clone =
5555
tree_clone.get_variant(parent_frame_);
56-
return std::make_unique<FixedOffsetFrame<ToScalar>>(
56+
auto new_frame = std::make_unique<FixedOffsetFrame<ToScalar>>(
5757
this->name(), parent_frame_clone, X_PF_, this->model_instance());
58+
new_frame->set_is_ephemeral(this->is_ephemeral());
59+
return new_frame;
5860
}
5961

6062
template <typename T>
@@ -78,8 +80,10 @@ FixedOffsetFrame<T>::DoCloneToScalar(
7880

7981
template <typename T>
8082
std::unique_ptr<Frame<T>> FixedOffsetFrame<T>::DoShallowClone() const {
81-
return std::make_unique<FixedOffsetFrame<T>>(this->name(), parent_frame_,
82-
X_PF_, this->model_instance());
83+
auto new_frame = std::make_unique<FixedOffsetFrame<T>>(
84+
this->name(), parent_frame_, X_PF_, this->model_instance());
85+
new_frame->set_is_ephemeral(this->is_ephemeral());
86+
return new_frame;
8387
}
8488

8589
template <typename T>

multibody/tree/fixed_offset_frame.h

-1
Original file line numberDiff line numberDiff line change
@@ -7,7 +7,6 @@
77
#include "drake/common/default_scalars.h"
88
#include "drake/common/eigen_types.h"
99
#include "drake/multibody/tree/frame.h"
10-
#include "drake/multibody/tree/multibody_tree_topology.h"
1110

1211
namespace drake {
1312
namespace multibody {

multibody/tree/mobilizer.h

+1
Original file line numberDiff line numberDiff line change
@@ -264,6 +264,7 @@ class Mobilizer : public MultibodyElement<T> {
264264
throw std::runtime_error(
265265
"The provided inboard and outboard frames reference the same object");
266266
}
267+
this->set_is_ephemeral(true); // Mobilizers are never added by users.
267268
}
268269

269270
~Mobilizer() override;

multibody/tree/multibody_element.h

+19
Original file line numberDiff line numberDiff line change
@@ -26,6 +26,14 @@ class MultibodyPlant;
2626
/// BodyIndex index() const { return this->template index_impl<BodyIndex>(); }
2727
/// @endcode
2828
///
29+
/// Some multibody elements are added during Finalize() and are not part of
30+
/// the user-specified model. These are called "ephemeral" elements and can
31+
/// be identified using the `is_ephemeral()` function here. Examples include
32+
/// - free joints added to connect lone bodies or free-floating trees
33+
/// to World
34+
/// - fixed offset frames added when joints are modeled by mobilizers
35+
/// - all mobilizers.
36+
///
2937
/// @tparam_default_scalar
3038
template <typename T>
3139
class MultibodyElement {
@@ -64,6 +72,15 @@ class MultibodyElement {
6472
/// @pre parameters != nullptr
6573
void SetDefaultParameters(systems::Parameters<T>* parameters) const;
6674

75+
/// Returns `true` if this %MultibodyElement was added during Finalize()
76+
/// rather than something a user added. (See class comments.)
77+
bool is_ephemeral() const { return is_ephemeral_; }
78+
79+
/// (Internal use only) Sets the `is_ephemeral` flag to the indicated value.
80+
/// The default if this is never called is `false`. Any element that is added
81+
/// during Finalize() should set this flag to `true`.
82+
void set_is_ephemeral(bool is_ephemeral) { is_ephemeral_ = is_ephemeral; }
83+
6784
protected:
6885
/// Default constructor made protected so that sub-classes can still declare
6986
/// their default constructors if they need to.
@@ -186,6 +203,8 @@ class MultibodyElement {
186203
// The default model instance id is *invalid*. This must be set to a
187204
// valid index value before the element is released to the wild.
188205
ModelInstanceIndex model_instance_;
206+
207+
bool is_ephemeral_{false};
189208
};
190209

191210
} // namespace multibody

multibody/tree/multibody_tree-inl.h

+9
Original file line numberDiff line numberDiff line change
@@ -72,6 +72,14 @@ const FrameType<T>& MultibodyTree<T>::AddFrame(
7272
return *result;
7373
}
7474

75+
template <typename T>
76+
template <template <typename Scalar> class FrameType>
77+
const FrameType<T>& MultibodyTree<T>::AddEphemeralFrame(
78+
std::unique_ptr<FrameType<T>> frame) {
79+
frame->set_is_ephemeral(true);
80+
return AddFrame(std::move(frame));
81+
}
82+
7583
template <typename T>
7684
template <template <typename Scalar> class FrameType, typename... Args>
7785
const FrameType<T>& MultibodyTree<T>::AddFrame(Args&&... args) {
@@ -228,6 +236,7 @@ const JointType<T>& MultibodyTree<T>::AddJoint(
228236
// during modeling are already in the graph.
229237
if (!is_ephemeral_joint) RegisterJointAndMaybeJointTypeInGraph(*joint.get());
230238

239+
joint->set_is_ephemeral(is_ephemeral_joint);
231240
joint->set_parent_tree(this, joints_.next_index());
232241
joint->set_ordinal(joints_.num_elements());
233242
JointType<T>* raw_joint_ptr = joint.get();

multibody/tree/multibody_tree.cc

+4-1
Original file line numberDiff line numberDiff line change
@@ -927,7 +927,10 @@ void MultibodyTree<T>::Finalize() {
927927
elements" to provide a uniform interface to the additional elements that were
928928
required to build the model. Below, we will augment the MultibodyPlant
929929
elements to match, so that advanced users can use the familiar Plant API to
930-
access and control these ephemeral elements. */
930+
access and control these ephemeral elements. The process of modeling Joints
931+
with available Mobilizers may introduce ephemeral Frames as well. All
932+
ephemeral elements must be marked as such in the base MultibodyElement class;
933+
public API element.is_ephemeral() is available to check. */
931934
link_joint_graph_.BuildForest();
932935
const LinkJointGraph& graph = link_joint_graph_;
933936

multibody/tree/multibody_tree.h

+15-7
Original file line numberDiff line numberDiff line change
@@ -205,6 +205,10 @@ class MultibodyTree {
205205
template <template <typename Scalar> class FrameType>
206206
const FrameType<T>& AddFrame(std::unique_ptr<FrameType<T>> frame);
207207

208+
// Same as above but sets the `is_ephemeral` bit.
209+
template <template <typename Scalar> class FrameType>
210+
const FrameType<T>& AddEphemeralFrame(std::unique_ptr<FrameType<T>> frame);
211+
208212
// Constructs a new frame with type `FrameType` with the given `args`, and
209213
// adds it to `this` %MultibodyTree, which retains ownership. The `FrameType`
210214
// will be specialized on the scalar type T of this %MultibodyTree.
@@ -977,14 +981,18 @@ class MultibodyTree {
977981
return forest().mobods(index);
978982
}
979983

980-
// This method must be called after all elements in the plant (joints, bodies,
981-
// force elements, constraints) were added and before any computations are
982-
// performed. It compiles all the necessary "topological information", i.e.
983-
// how bodies, mobilizers, and any other elements connect with each other, and
984-
// performs all the required pre-processing to permit efficient computations
985-
// at a later stage.
984+
// Finalize() must be called after all user-defined elements in the plant
985+
// (joints, bodies, force elements, constraints, etc.) have been added and
986+
// before any computations are performed. It compiles all the necessary
987+
// topological information, i.e. how bodies, mobilizers, and any other
988+
// elements connect with each other, and performs all the required
989+
// pre-processing to permit efficient computations at a later stage. During
990+
// this process, we may add additional elements (e.g. joints, frames,
991+
// and constraints) to facilitate computation; we call those "ephemeral"
992+
// elements and mark them as such in the base MultibodyElement class to
993+
// distinguish them from user-defined elements.
986994
//
987-
// If the finalize stage is successful, the topology of this MultibodyTree
995+
// If the Finalize operation is successful, the topology of this MultibodyTree
988996
// is validated, meaning that the topology is up-to-date after this call.
989997
// No more multibody plant elements can be added after a call to Finalize().
990998
//

multibody/tree/test/frames_test.cc

+12-4
Original file line numberDiff line numberDiff line change
@@ -70,16 +70,20 @@ class FrameTests : public ::testing::Test {
7070
// Frame Q is rigidly attached to P with pose X_PQ.
7171
frameQ_ = &model->AddFrame<FixedOffsetFrame>("Q", *frameP_, X_PQ_);
7272

73-
// Frame R is arbitrary, but named.
73+
// Frame R is arbitrary, but named and not ephemeral.
7474
frameR_ = &model->AddFrame<FixedOffsetFrame>(
7575
"R", *frameP_, math::RigidTransformd::Identity());
76+
EXPECT_FALSE(frameR_->is_ephemeral());
7677

77-
// Frame S is arbitrary, but named and with a specific model instance.
78+
// Frame S is arbitrary, but named, with a specific model instance, and
79+
// ephemeral.
7880
X_WS_ = X_BP_; // Any non-identity pose will do.
7981
extra_instance_ = model->AddModelInstance("extra_instance");
80-
frameS_ = &model->AddFrame<FixedOffsetFrame>("S", model->world_frame(),
81-
X_WS_, extra_instance_);
82+
frameS_ =
83+
&model->AddEphemeralFrame(std::make_unique<FixedOffsetFrame<double>>(
84+
"S", model->world_frame(), X_WS_, extra_instance_));
8285
EXPECT_EQ(frameS_->scoped_name().get_full(), "extra_instance::S");
86+
EXPECT_TRUE(frameS_->is_ephemeral());
8387

8488
// Ensure that the model instance propagates implicitly.
8589
frameSChild_ = &model->AddFrame<FixedOffsetFrame>(
@@ -351,13 +355,15 @@ TEST_F(FrameTests, ShallowCloneTests) {
351355
EXPECT_NE(dynamic_cast<const RigidBodyFrame<double>*>(frameB_), nullptr);
352356
EXPECT_EQ(clone_of_frameB->name(), frameB_->name());
353357
EXPECT_EQ(clone_of_frameB->model_instance(), frameB_->model_instance());
358+
EXPECT_FALSE(clone_of_frameB->is_ephemeral());
354359

355360
// Make sure ShallowClone() preserves FixedOffsetFrame frameS's properties.
356361
const std::unique_ptr<Frame<double>> clone_of_frameS =
357362
frameS_->ShallowClone();
358363
EXPECT_NE(clone_of_frameS.get(), frameS_);
359364
EXPECT_EQ(clone_of_frameS->name(), frameS_->name());
360365
EXPECT_EQ(clone_of_frameS->model_instance(), frameS_->model_instance());
366+
EXPECT_TRUE(clone_of_frameS->is_ephemeral());
361367
const auto& downcast_clone =
362368
dynamic_cast<const FixedOffsetFrame<double>&>(*clone_of_frameS);
363369
EXPECT_TRUE(downcast_clone.GetFixedPoseInBodyFrame().IsExactlyEqualTo(X_WS_));
@@ -373,12 +379,14 @@ TEST_F(FrameTests, DeepCloneTests) {
373379
nullptr);
374380
EXPECT_EQ(clone_of_frameB.name(), frameB_->name());
375381
EXPECT_EQ(clone_of_frameB.model_instance(), frameB_->model_instance());
382+
EXPECT_FALSE(clone_of_frameB.is_ephemeral());
376383

377384
// Make sure CloneToScalar() preserves FixedOffsetFrame frameS's properties.
378385
const Frame<AutoDiffXd>& clone_of_frameS =
379386
cloned_tree->get_frame(frameS_->index());
380387
EXPECT_EQ(clone_of_frameS.name(), frameS_->name());
381388
EXPECT_EQ(clone_of_frameS.model_instance(), frameS_->model_instance());
389+
EXPECT_TRUE(clone_of_frameS.is_ephemeral());
382390
const auto& downcast_clone =
383391
dynamic_cast<const FixedOffsetFrame<AutoDiffXd>&>(clone_of_frameS);
384392
EXPECT_TRUE(downcast_clone.GetFixedPoseInBodyFrame().IsExactlyEqualTo(

multibody/tree/test/revolute_mobilizer_test.cc

+2
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,8 @@ class RevoluteMobilizerTest : public MobilizerTester {
3434
std::make_unique<RevoluteJoint<double>>(
3535
"joint0", tree().world_body().body_frame(), body_->body_frame(),
3636
axis_F_));
37+
// Mobilizers are always ephemeral (i.e. not added by user).
38+
EXPECT_TRUE(mobilizer_->is_ephemeral());
3739
mutable_mobilizer_ = const_cast<RevoluteMobilizer<double>*>(mobilizer_);
3840
}
3941

0 commit comments

Comments
 (0)