Skip to content

Commit

Permalink
multibody: Rename parameters of WeldJoint() and WeldFrames() (RobotLo…
Browse files Browse the repository at this point in the history
…comotion#14805)

* multibody: Rename parameters of WeldJoint() and WeldFrames()

Closes RobotLocomotion#14641.

The parameter names were variously confusing (WeldFrames, see RobotLocomotion#14641)
and/or inconsistent with other joints (WeldJoint constructor).

This patch moves both entry points to use naming more consistent with
other joint APIs and deprecates the old parameter names in python
bindings.
  • Loading branch information
rpoyner-tri authored Mar 23, 2021
1 parent e58c479 commit 67243a9
Show file tree
Hide file tree
Showing 7 changed files with 128 additions and 36 deletions.
14 changes: 14 additions & 0 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -246,6 +246,20 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def("WeldFrames",
py::overload_cast<const Frame<T>&, const Frame<T>&,
const RigidTransform<double>&>(&Class::WeldFrames),
py::arg("frame_on_parent_P"), py::arg("frame_on_child_C"),
py::arg("X_PC") = RigidTransform<double>::Identity(),
py_rvp::reference_internal, cls_doc.WeldFrames.doc)
.def(
"WeldFrames",
[](Class* self, const Frame<T>& A, const Frame<T>& B,
const RigidTransform<double>& X_AB) -> const WeldJoint<T>& {
WarnDeprecated(
"Please use MultibodyPlant.WeldFrames("
"frame_on_parent_P=value1, frame_on_child_C=value2,"
" X_PC=value3) instead. This variant will be removed"
" after 2021-07-01.");
return self->WeldFrames(A, B, X_AB);
},
py::arg("A"), py::arg("B"),
py::arg("X_AB") = RigidTransform<double>::Identity(),
py_rvp::reference_internal, cls_doc.WeldFrames.doc)
Expand Down
88 changes: 74 additions & 14 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -1183,12 +1183,15 @@ def test_model_instance_state_access(self, T):
X_EeGripper = RigidTransform_[float](
RollPitchYaw_[float](np.pi / 2, 0, np.pi / 2), [0, 0, 0.081])
plant_f.WeldFrames(
A=plant_f.world_frame(),
B=plant_f.GetFrameByName("iiwa_link_0", iiwa_model))
frame_on_parent_P=plant_f.world_frame(),
frame_on_child_C=plant_f.GetFrameByName("iiwa_link_0", iiwa_model),
X_PC=RigidTransform_[float]())
# Perform the second weld without named arguments to ensure that the
# proper binding gets invoked.
plant_f.WeldFrames(
A=plant_f.GetFrameByName("iiwa_link_7", iiwa_model),
B=plant_f.GetFrameByName("body", gripper_model),
X_AB=X_EeGripper)
plant_f.GetFrameByName("iiwa_link_7", iiwa_model),
plant_f.GetFrameByName("body", gripper_model),
X_EeGripper)
plant_f.Finalize()
plant = to_type(plant_f, T)

Expand Down Expand Up @@ -1301,6 +1304,42 @@ def test_model_instance_state_access(self, T):
numpy_compare.assert_float_equal(plant.GetPositionsAndVelocities(
context, iiwa_model), np.zeros(nq_iiwa + nv_iiwa))

@numpy_compare.check_all_types
def test_deprecated_weld_frames_variant(self, T):
# Tests deprecated parameter names variant of WeldFrames(); remove
# after 2021-07-01.

# N.B. Please check warning above in `check_multibody_state_access`.
MultibodyPlant = MultibodyPlant_[T]
# Create a MultibodyPlant with a kuka arm and a schunk gripper.
# the arm is welded to the world, the gripper is welded to the
# arm's end effector.
wsg50_sdf_path = FindResourceOrThrow(
"drake/manipulation/models/"
"wsg_50_description/sdf/schunk_wsg_50.sdf")
iiwa_sdf_path = FindResourceOrThrow(
"drake/manipulation/models/"
"iiwa_description/sdf/iiwa14_no_collision.sdf")

timestep = 0.0002
# N.B. `Parser` only supports `MultibodyPlant_[float]`.
plant_f = MultibodyPlant_[float](timestep)
parser = Parser(plant_f)

iiwa_model = parser.AddModelFromFile(
file_name=iiwa_sdf_path, model_name='robot')
gripper_model = parser.AddModelFromFile(
file_name=wsg50_sdf_path, model_name='gripper')

# Weld the base of arm and gripper to reduce the number of states.
X_EeGripper = RigidTransform_[float](
RollPitchYaw_[float](np.pi / 2, 0, np.pi / 2), [0, 0, 0.081])
with catch_drake_warnings(expected_count=1):
plant_f.WeldFrames(
A=plant_f.world_frame(),
B=plant_f.GetFrameByName("iiwa_link_0", iiwa_model),
X_AB=RigidTransform())

@numpy_compare.check_all_types
def test_model_instance_state_access_by_array(self, T):
# N.B. Please check warning above in `check_multibody_state_access`.
Expand Down Expand Up @@ -1329,12 +1368,13 @@ def test_model_instance_state_access_by_array(self, T):
X_EeGripper = RigidTransform_[float](
RollPitchYaw_[float](np.pi / 2, 0, np.pi / 2), [0, 0, 0.081])
plant_f.WeldFrames(
A=plant_f.world_frame(),
B=plant_f.GetFrameByName("iiwa_link_0", iiwa_model))
frame_on_parent_P=plant_f.world_frame(),
frame_on_child_C=plant_f.GetFrameByName("iiwa_link_0", iiwa_model))
plant_f.WeldFrames(
A=plant_f.GetFrameByName("iiwa_link_7", iiwa_model),
B=plant_f.GetFrameByName("body", gripper_model),
X_AB=X_EeGripper)
frame_on_parent_P=plant_f.GetFrameByName(
"iiwa_link_7", iiwa_model),
frame_on_child_C=plant_f.GetFrameByName("body", gripper_model),
X_PC=X_EeGripper)
plant_f.Finalize()
plant = to_type(plant_f, T)

Expand Down Expand Up @@ -1521,22 +1561,42 @@ def make_universal_joint(plant, P, C):
)

def make_weld_joint(plant, P, C):
# TODO(eric.cousineau): Update WeldJoint arg names to be consistent
# with other joints.
return WeldJoint_[T](
name="weld",
parent_frame_P=P,
child_frame_C=C,
frame_on_parent_P=P,
frame_on_child_C=C,
X_PC=X_PC,
)

def make_deprecated_weld_joint(plant, P, C):
# Tests deprecated parameter name variant; remove after 2021-07-01.
with catch_drake_warnings(expected_count=1):
return WeldJoint_[T](
name="weld",
parent_frame_P=P,
child_frame_C=C,
X_PC=X_PC,
)

def make_noparams_weld_joint(plant, P, C):
# Tests deprecated parameter name variant does not interfere;
# remove after 2021-07-01.
return WeldJoint_[T](
"weld",
P,
C,
X_PC,
)

make_joint_list = [
make_ball_rpy_joint,
make_planar_joint,
make_prismatic_joint,
make_revolute_joint,
make_universal_joint,
make_weld_joint,
make_deprecated_weld_joint,
make_noparams_weld_joint,
]

for make_joint in make_joint_list:
Expand Down
12 changes: 12 additions & 0 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -617,6 +617,18 @@ void DoScalarDependentDefinitions(py::module m, T) {
cls // BR
.def(py::init<const string&, const Frame<T>&, const Frame<T>&,
const RigidTransform<double>&>(),
py::arg("name"), py::arg("frame_on_parent_P"),
py::arg("frame_on_child_C"), py::arg("X_PC"), cls_doc.ctor.doc)
.def(py::init([](const string& name, const Frame<T>& parent_frame_P,
const Frame<T>& child_frame_C,
const RigidTransform<double>& X_PC) {
WarnDeprecated(
"Please use WeldJoint(frame_on_parent_P=value1,"
" frame_on_child_C=value2, X_PC=value3) instead. This variant"
" will be removed after 2021-07-01.");
return std::make_unique<Class>(
name, parent_frame_P, child_frame_C, X_PC);
}),
py::arg("name"), py::arg("parent_frame_P"),
py::arg("child_frame_C"), py::arg("X_PC"), cls_doc.ctor.doc)
.def(
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/systems/test/meshcat_visualizer_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -421,9 +421,9 @@ def test_contact_force(self):

# Weld table to world.
plant.WeldFrames(
A=plant.world_frame(),
B=plant.GetFrameByName("link", table_model),
X_AB=RigidTransform(RotationMatrix.MakeXRotation(0.2)))
frame_on_parent_P=plant.world_frame(),
frame_on_child_C=plant.GetFrameByName("link", table_model),
X_PC=RigidTransform(RotationMatrix.MakeXRotation(0.2)))

plant.Finalize()

Expand Down
20 changes: 12 additions & 8 deletions multibody/plant/multibody_plant.h
Original file line number Diff line number Diff line change
Expand Up @@ -1018,14 +1018,18 @@ class MultibodyPlant : public internal::MultibodyTreeSystem<T> {
return joint;
}

/// Welds frames A and B with relative pose `X_AB`. That is, the pose of
/// frame B in frame A is fixed, with value `X_AB`.
/// The call to this method creates and adds a new WeldJoint to the model.
/// The new WeldJoint is named as: A.name() + "_welds_to_" + B.name().
/// @returns a constant reference to the WeldJoint welding frames A and B.
const WeldJoint<T>& WeldFrames(const Frame<T>& A, const Frame<T>& B,
const math::RigidTransform<double>& X_AB =
math::RigidTransform<double>::Identity());
/// Welds `frame_on_parent_P` and `frame_on_child_C` with relative pose
/// `X_PC`. That is, the pose of frame C in frame P is fixed, with value
/// `X_PC`. If `X_PC` is omitted, the identity transform will be used. The
/// call to this method creates and adds a new WeldJoint to the model. The
/// new WeldJoint is named as: P.name() + "_welds_to_" + C.name().
/// @returns a constant reference to the WeldJoint welding frames
/// P and C.
/// @throws std::exception if the weld produces a duplicate joint name.
const WeldJoint<T>& WeldFrames(const Frame<T>& frame_on_parent_P,
const Frame<T>& frame_on_child_C,
const math::RigidTransform<double>& X_PC =
math::RigidTransform<double>::Identity());

/// Adds a new force element model of type `ForceElementType` to `this`
/// %MultibodyPlant. The arguments to this method `args` are forwarded to
Expand Down
12 changes: 6 additions & 6 deletions multibody/tree/weld_joint.h
Original file line number Diff line number Diff line change
Expand Up @@ -28,13 +28,13 @@ class WeldJoint final : public Joint<T> {

static const char kTypeName[];

/// Constructor for a %WeldJoint between a `parent_frame_P` and a
/// `child_frame_C` so that their relative pose `X_PC` is fixed as if they
/// were "welded" together.
WeldJoint(const std::string& name, const Frame<T>& parent_frame_P,
const Frame<T>& child_frame_C,
/// Constructor for a %WeldJoint between a `frame_on_parent_P` and a
/// `frame_on_child_C` so that their relative pose `X_PC` is fixed as if
/// they were "welded" together.
WeldJoint(const std::string& name, const Frame<T>& frame_on_parent_P,
const Frame<T>& frame_on_child_C,
const math::RigidTransform<double>& X_PC)
: Joint<T>(name, parent_frame_P, child_frame_C,
: Joint<T>(name, frame_on_parent_P, frame_on_child_C,
VectorX<double>() /* no pos lower limits */,
VectorX<double>() /* no pos upper limits */,
VectorX<double>() /* no vel lower limits */,
Expand Down
12 changes: 7 additions & 5 deletions tutorials/rendering_multibody_plant.ipynb
Original file line number Diff line number Diff line change
Expand Up @@ -169,8 +169,9 @@
"source": [
"iiwa_1 = parser.AddModelFromFile(iiwa_file, model_name=\"iiwa_1\")\n",
"plant.WeldFrames(\n",
" plant.world_frame(), plant.GetFrameByName(\"iiwa_link_0\", iiwa_1),\n",
" X_AB=xyz_rpy_deg([0, 0, 0], [0, 0, 0]))"
" frame_on_parent_P=plant.world_frame(),\n",
" frame_on_child_C=plant.GetFrameByName(\"iiwa_link_0\", iiwa_1),\n",
" X_PC=xyz_rpy_deg([0, 0, 0], [0, 0, 0]))"
]
},
{
Expand All @@ -188,8 +189,9 @@
"source": [
"iiwa_2 = parser.AddModelFromFile(iiwa_file, model_name=\"iiwa_2\")\n",
"plant.WeldFrames(\n",
" plant.world_frame(), plant.GetFrameByName(\"iiwa_link_0\", iiwa_2),\n",
" X_AB=xyz_rpy_deg([0, 1, 0], [0, 0, 0]))"
" frame_on_parent_P=plant.world_frame(),\n",
" frame_on_child_C=plant.GetFrameByName(\"iiwa_link_0\", iiwa_2),\n",
" X_PC=xyz_rpy_deg([0, 1, 0], [0, 0, 0]))"
]
},
{
Expand Down Expand Up @@ -481,4 +483,4 @@
},
"nbformat": 4,
"nbformat_minor": 2
}
}

0 comments on commit 67243a9

Please sign in to comment.