Skip to content

Commit

Permalink
[pybind] Add MultibodyPlant::CalcRelativeRotationMatrix. (RobotLocomo…
Browse files Browse the repository at this point in the history
  • Loading branch information
hongkai-dai authored and RussTedrake committed Dec 15, 2024
1 parent 5825b8b commit 8cea254
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 2 deletions.
5 changes: 4 additions & 1 deletion bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -715,7 +715,10 @@ void DoScalarDependentDefinitions(py::module m, T) {
py::arg("context"), py::arg("qdot"), cls_doc.MapQDotToVelocity.doc)
.def("CalcRelativeTransform", &Class::CalcRelativeTransform,
py::arg("context"), py::arg("frame_A"), py::arg("frame_B"),
cls_doc.CalcRelativeTransform.doc);
cls_doc.CalcRelativeTransform.doc)
.def("CalcRelativeRotationMatrix", &Class::CalcRelativeRotationMatrix,
py::arg("context"), py::arg("frame_A"), py::arg("frame_B"),
cls_doc.CalcRelativeRotationMatrix.doc);
if constexpr (std::is_same_v<T, double>) {
cls // BR
.def("MakeVelocityToQDotMap", &Class::MakeVelocityToQDotMap,
Expand Down
5 changes: 4 additions & 1 deletion bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -1142,8 +1142,11 @@ def do_test_multibody_tree_kinematics(self, T, time_step):
base = plant.GetBodyByName("base")
base_frame = plant.GetFrameByName("base")
X_WL = plant.CalcRelativeTransform(
context, frame_A=world_frame, frame_B=base_frame)
context=context, frame_A=world_frame, frame_B=base_frame)
self.assertIsInstance(X_WL, RigidTransform)
R_WL = plant.CalcRelativeRotationMatrix(
context=context, frame_A=world_frame, frame_B=base_frame)
self.assertIsInstance(R_WL, RotationMatrix_[T])
free_bodies = plant.GetFloatingBaseBodies()
self.assertEqual(len(free_bodies), 1)
self.assertTrue(base.index() in free_bodies)
Expand Down

0 comments on commit 8cea254

Please sign in to comment.