Skip to content

Commit

Permalink
Allow reversed weld joints.
Browse files Browse the repository at this point in the history
  • Loading branch information
sherm1 committed Nov 4, 2024
1 parent d6ff6cc commit 7d780b4
Show file tree
Hide file tree
Showing 3 changed files with 63 additions and 18 deletions.
62 changes: 51 additions & 11 deletions multibody/plant/test/multibody_plant_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1707,9 +1707,10 @@ GTEST_TEST(MultibodyPlantTest, GetBodiesKinematicallyAffectedBy) {

// Weld a body to World but with the body as the parent and World as the
// child. This is fine but must be implemented with a reversed Weld
// mobilizer that specifies World as the inboard body. Drake doesn't support
// that yet.
// TODO(sherm1) Remove this restriction and fix the test.
// mobilizer that specifies World as the inboard body. We'll also add an
// identical rigid body with the frames in the common order and check that
// the reaction forces are the same on body bodies but negated and shifted
// to be reported always on the joint's child body.
GTEST_TEST(MultibodyPlantTest, ReversedWeldJoint) {
// This test expects that the following model has a world body and a pair of
// welded-together bodies.
Expand All @@ -1718,15 +1719,54 @@ GTEST_TEST(MultibodyPlantTest, ReversedWeldJoint) {
MultibodyPlant<double> plant(0.0);
Parser(&plant).AddModelsFromUrl(sdf_url);

// Add a new body, and weld it in the wrong direction using `WeldFrames`.
const RigidBody<double>& extra = plant.AddRigidBody(
"extra", default_model_instance(), SpatialInertia<double>::NaN());
plant.WeldFrames(extra.body_frame(), plant.world_frame());
// Rotate 90° and shift by 2 so we can verify that reaction force
// gets properly re-expressed and shifted for the reverse case.
const RigidTransformd X_FM(RollPitchYawd(M_PI/2, 0, 0),
Vector3d(2, 0, 0));

// Weld a body with parent=world, child=forward_body. Mobilizer
// inboard/outboard ordering will match. Reaction reported on "forward_body".
const RigidBody<double>& forward_body =
plant.AddRigidBody("forward_body", default_model_instance(),
SpatialInertia<double>::MakeUnitary());
auto& forward_weld = plant.AddJoint<WeldJoint>(
"forward_weld", plant.world_body(), {}, forward_body, {}, X_FM);

// Weld a body with parent=reverse_body, child=world. Mobilizer
// inboard/outboard ordering will be reversed. Reaction reported on
// "reverse_body".
const RigidBody<double>& reverse_body =
plant.AddRigidBody("reverse_body", default_model_instance(),
SpatialInertia<double>::MakeUnitary());
auto& reverse_weld = plant.AddJoint<WeldJoint>(
"reverse_weld", reverse_body, {}, plant.world_body(), {}, X_FM);

plant.Finalize();
auto context = plant.CreateDefaultContext();

DRAKE_EXPECT_THROWS_MESSAGE(plant.Finalize(),
".*Finalize.*: parent/child ordering.*"
"Joint extra_welds_to_world.*WorldModelInstance.*"
"would have to be reversed.*");
const std::vector<SpatialForce<double>>& reaction_forces =
plant.get_reaction_forces_output_port()
.Eval<std::vector<SpatialForce<double>>>(*context);

const double g = 9.81; // Our default gravity.

// In the forward case, forward_body's frame is the joint's M frame and has
// been rotated 90° about x so that the y axis now points in World's +z
// direction. Mass is 1 and gravity is in -y (World -z) so the force holding
// up forward body is g in the +y direction. We're shifted by 2 along x but
// we're looking at the reaction on forward_body at its origin (and COM) so
// there is no moment.
EXPECT_TRUE(reaction_forces[forward_weld.ordinal()].IsApprox(
SpatialForce<double>(Vector3d(0, 0, 0), Vector3d(0, g, 0)), 1e-14));

// In the reverse case, reverse_body's body frame is the F frame and M is
// the World frame. The same transform applied to M moves the reverse body
// in the opposite direction. Gravity continues to be in World -z (and the
// force on World is in -z). But reverse_body's COM is now at -2 x producing
// a moment -2g around World's y axis, which it resists with a moment +2g.
EXPECT_TRUE(reaction_forces[reverse_weld.ordinal()].IsApprox(
SpatialForce<double>(Vector3d(0, 2 * g, 0), Vector3d(0, 0, -g)),
1e-14));
}

// Verifies exact set of output ports we expect to be a direct feedthrough of
Expand Down
14 changes: 8 additions & 6 deletions multibody/tree/multibody_tree.cc
Original file line number Diff line number Diff line change
Expand Up @@ -775,16 +775,18 @@ void MultibodyTree<T>::CreateJointImplementations() {
forest().joints(mobod.joint_ordinal()).index();
Joint<T>& joint = joints_.get_mutable_element(joint_index);

// Currently we allow a reversed mobilizer only for Weld joints.
// TODO(sherm1) Remove this restriction.
if (mobod.is_reversed()) {
if (mobod.is_reversed() && !mobod.is_weld()) {
throw std::runtime_error(fmt::format(
"MultibodyPlant::Finalize(): parent/child ordering for "
"Joint {} in model instance {} would have to be reversed "
"{} joint {} in model instance {} would have to be reversed "
"to make a tree-structured model for this system. "
"Currently Drake does not support that. Reverse the "
"ordering in your joint definition so that all "
"parent/child directions form a tree structure.",
joint.name(), GetModelInstanceName(joint.model_instance())));
"Currently Drake does not support that except for Weld "
"joints. Reverse the ordering in your joint definition so "
"that all parent/child directions form a tree structure.",
joint.type_name(), joint.name(),
GetModelInstanceName(joint.model_instance())));
}

Mobilizer<T>* mobilizer =
Expand Down
5 changes: 4 additions & 1 deletion multibody/tree/weld_joint.cc
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,10 @@ WeldJoint<T>::MakeImplementationBlueprint(
auto blue_print = std::make_unique<typename Joint<T>::BluePrint>();
const auto [inboard_frame, outboard_frame] =
this->tree_frames(mobod.is_reversed());
// TODO(sherm1) The mobilizer needs to be reversed, not just the frames.
// The only other requirement for a reversed weld is that the reported
// reaction forces (on the joint's child link) must be those acting on
// the mobilizer's inboard body rather than the usual outboard reaction.
// That's handled when reporting, not locally by the mobilizer.
blue_print->mobilizer = std::make_unique<internal::WeldMobilizer<T>>(
mobod, *inboard_frame, *outboard_frame, X_FM_);
return blue_print;
Expand Down

0 comments on commit 7d780b4

Please sign in to comment.