Skip to content

Commit

Permalink
[pydrake] Bind Joint.kTypeName constants (#21896)
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Sep 12, 2024
1 parent 59a15c3 commit b28b5dc
Show file tree
Hide file tree
Showing 3 changed files with 26 additions and 3 deletions.
10 changes: 7 additions & 3 deletions bindings/pydrake/examples/gym/envs/cart_pole.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,6 +30,10 @@
MultibodyPlant,
MultibodyPlantConfig,
)
from pydrake.multibody.tree import (
PrismaticJoint,
RevoluteJoint,
)
from pydrake.systems.analysis import Simulator
from pydrake.systems.drawing import plot_graphviz, plot_system_graphviz
from pydrake.systems.framework import (
Expand Down Expand Up @@ -338,14 +342,14 @@ def reset_handler(simulator, diagram_context, seed):
# Ensure the positions are within the joint limits.
for pair in home_positions:
joint = plant.GetJointByName(pair[0])
if joint.type_name() == "revolute":
if joint.type_name() == RevoluteJoint.kTypeName:
joint.set_angle(plant_context,
np.clip(pair[1],
joint.position_lower_limit(),
joint.position_upper_limit()
)
)
if joint.type_name() == "prismatic":
if joint.type_name() == PrismaticJoint.kTypeName:
joint.set_translation(plant_context,
np.clip(pair[1],
joint.position_lower_limit(),
Expand All @@ -354,7 +358,7 @@ def reset_handler(simulator, diagram_context, seed):
)
for pair in home_velocities:
joint = plant.GetJointByName(pair[0])
if joint.type_name() == "revolute":
if joint.type_name() == RevoluteJoint.kTypeName:
joint.set_angular_rate(plant_context,
np.clip(pair[1],
joint.velocity_lower_limit(),
Expand Down
1 change: 1 addition & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -654,6 +654,7 @@ def _test_joint_api(self, T, joint):
self._test_multibody_tree_element_mixin(T, joint)
self.assertIsInstance(joint.name(), str)
self.assertIsInstance(joint.type_name(), str)
self.assertEqual(joint.type_name(), joint.kTypeName)
self.assertIsInstance(joint.parent_body(), Body)
self.assertIsInstance(joint.child_body(), Body)
self.assertIsInstance(joint.frame_on_parent(), Frame)
Expand Down
18 changes: 18 additions & 0 deletions bindings/pydrake/multibody/tree_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -492,6 +492,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "BallRpyJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(
py::init<const string&, const Frame<T>&, const Frame<T>&, double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -523,6 +525,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "PlanarJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&,
Vector3<double>>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -572,6 +576,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "PrismaticJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&,
const Vector3<double>&, double, double, double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -628,6 +634,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "QuaternionFloatingJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&, double,
double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -688,6 +696,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "RevoluteJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&,
const Vector3<double>&, double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -744,6 +754,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "RpyFloatingJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&, double,
double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -801,6 +813,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "ScrewJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&, double,
double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -854,6 +868,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "UniversalJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(
py::init<const string&, const Frame<T>&, const Frame<T>&, double>(),
py::arg("name"), py::arg("frame_on_parent"),
Expand Down Expand Up @@ -884,6 +900,8 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class, Joint<T>>(
m, "WeldJoint", param, cls_doc.doc);
cls // BR
.def_property_readonly_static(
"kTypeName", [](py::object /* self */) { return Class::kTypeName; })
.def(py::init<const string&, const Frame<T>&, const Frame<T>&,
const RigidTransform<double>&>(),
py::arg("name"), py::arg("frame_on_parent_F"),
Expand Down

0 comments on commit b28b5dc

Please sign in to comment.