Skip to content

Commit

Permalink
mkdoc: Add additional overload disambiguation (RobotLocomotion#10289)
Browse files Browse the repository at this point in the history
Add several more heuristics for how to name the docstrings for overloaded
methods.  Add an opt-out for Doxygen comments to remove themselves from mkdoc
consideration.  Remove the "doc_1", "doc_2", etc. fallback, so that if we can't
figure out good names, we produce _no_ names and make the developer figure out
a better solution.

Add a few Doxygen comments so that pydrake strings make a little more sense.

Opt-out some current Doxygen comments from mkdoc, in order to make overload
name assignment successful.

Port all of the pydrake/bindings to use the new names.
  • Loading branch information
jwnimmer-tri authored Jan 3, 2019
1 parent 2df2d25 commit 5336c31
Show file tree
Hide file tree
Showing 70 changed files with 664 additions and 353 deletions.
2 changes: 2 additions & 0 deletions attic/multibody/rigid_body_plant/compliant_material.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,8 @@ namespace systems {
class CompliantMaterial {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(CompliantMaterial)

/** Constructs a default material. */
CompliantMaterial() = default;

/** Constructs fully specified material. Will throw an exception in any of the
Expand Down
1 change: 1 addition & 0 deletions automotive/simple_car.h
Original file line number Diff line number Diff line change
Expand Up @@ -57,6 +57,7 @@ class SimpleCar final : public systems::LeafSystem<T> {
public:
DRAKE_NO_COPY_NO_MOVE_NO_ASSIGN(SimpleCar)

/** Constructs a default car. */
SimpleCar();

/// Scalar-converting copy constructor. See @ref system_scalar_conversion.
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/attic/solvers/ik_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ PYBIND11_MODULE(ik, m) {
static_cast<void (PostureConstraint::*)( // NOLINT
const Eigen::VectorXi&, const Eigen::VectorXd&,
const Eigen::VectorXd&)>(&PostureConstraint::setJointLimits),
doc.PostureConstraint.setJointLimits.doc_3args);
doc.PostureConstraint.setJointLimits.doc);

py::class_<WorldPositionConstraint, RigidBodyConstraint>(
m, "_WorldPositionConstraint", doc.WorldPositionConstraint.doc)
Expand Down Expand Up @@ -141,10 +141,10 @@ PYBIND11_MODULE(ik, m) {
static_cast<void (QuasiStaticConstraint::*)( // NOLINT
std::vector<int>, const Eigen::Matrix3Xd&)>(
&QuasiStaticConstraint::addContact),
doc.QuasiStaticConstraint.addContact.doc_2args);
doc.QuasiStaticConstraint.addContact.doc);

py::class_<IKoptions>(m, "IKoptions", doc.IKoptions.doc)
.def(py::init<RigidBodyTree<double>*>(), doc.IKoptions.ctor.doc_1args)
.def(py::init<RigidBodyTree<double>*>(), doc.IKoptions.ctor.doc)
.def("setQ", &IKoptions::setQ, doc.IKoptions.setQ.doc)
.def("getQ", &IKoptions::getQ, doc.IKoptions.getQ.doc)
.def("setQa", &IKoptions::setQa, doc.IKoptions.setQa.doc)
Expand Down
10 changes: 5 additions & 5 deletions bindings/pydrake/automotive_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -94,7 +94,7 @@ PYBIND11_MODULE(automotive, m) {
// TODO(eric.cousineau) Bind this named vector automatically (see #8096).
py::class_<DrivingCommand<T>, BasicVector<T>>(
m, "DrivingCommand", doc.DrivingCommand.doc)
.def(py::init<>(), doc.DrivingCommand.ctor.doc_0args)
.def(py::init<>(), doc.DrivingCommand.ctor.doc)
.def("steering_angle", &DrivingCommand<T>::steering_angle,
doc.DrivingCommand.steering_angle.doc)
.def("acceleration", &DrivingCommand<T>::acceleration,
Expand All @@ -110,7 +110,7 @@ PYBIND11_MODULE(automotive, m) {
RoadPositionStrategy, double>(),
py::arg("road"), py::arg("path_or_branches"),
py::arg("road_position_strategy"), py::arg("period_sec"),
doc.IdmController.ctor.doc_4args)
doc.IdmController.ctor.doc)
.def("ego_pose_input", &IdmController<T>::ego_pose_input,
py_reference_internal, doc.IdmController.ego_pose_input.doc)
.def("ego_velocity_input", &IdmController<T>::ego_velocity_input,
Expand Down Expand Up @@ -150,7 +150,7 @@ PYBIND11_MODULE(automotive, m) {

py::class_<PurePursuitController<T>, LeafSystem<T>>(
m, "PurePursuitController", doc.PurePursuitController.doc)
.def(py::init<>(), doc.PurePursuitController.ctor.doc_4)
.def(py::init<>(), doc.PurePursuitController.ctor.doc)
.def("ego_pose_input", &PurePursuitController<T>::ego_pose_input,
py_reference_internal, doc.PurePursuitController.ego_pose_input.doc)
.def("lane_input", &PurePursuitController<T>::lane_input,
Expand All @@ -163,7 +163,7 @@ PYBIND11_MODULE(automotive, m) {
// TODO(eric.cousineau) Bind this named vector automatically (see #8096).
py::class_<SimpleCarState<T>, BasicVector<T>>(
m, "SimpleCarState", doc.SimpleCarState.doc)
.def(py::init<>(), doc.SimpleCarState.ctor.doc_0args)
.def(py::init<>(), doc.SimpleCarState.ctor.doc)
.def("x", &SimpleCarState<T>::x, doc.SimpleCarState.x.doc)
.def("y", &SimpleCarState<T>::y, doc.SimpleCarState.y.doc)
.def("heading", &SimpleCarState<T>::heading,
Expand All @@ -178,7 +178,7 @@ PYBIND11_MODULE(automotive, m) {
doc.SimpleCarState.set_velocity.doc);

py::class_<SimpleCar<T>, LeafSystem<T>>(m, "SimpleCar", doc.SimpleCar.doc)
.def(py::init<>(), doc.SimpleCar.ctor.doc_4)
.def(py::init<>(), doc.SimpleCar.ctor.doc)
.def("state_output", &SimpleCar<T>::state_output, py_reference_internal,
doc.SimpleCar.state_output.doc)
.def("pose_output", &SimpleCar<T>::pose_output, py_reference_internal,
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/common/type_safe_index_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -17,7 +17,7 @@ auto BindTypeSafeIndex(
py::module m, const std::string& name, const std::string& class_doc = "") {
py::class_<Type> cls(m, name.c_str(), class_doc.c_str());
cls // BR
.def(py::init<int>(), pydrake_doc.drake.TypeSafeIndex.ctor.doc_2)
.def(py::init<int>(), pydrake_doc.drake.TypeSafeIndex.ctor.doc_0args)
.def("__int__", &Type::operator int)
.def("__eq__",
[](const Type* self, const Type* other) { return *self == *other; },
Expand Down
8 changes: 4 additions & 4 deletions bindings/pydrake/examples/acrobot_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ PYBIND11_MODULE(acrobot, m) {

py::class_<AcrobotPlant<T>, LeafSystem<T>>(
m, "AcrobotPlant", doc.AcrobotPlant.doc)
.def(py::init<>(), doc.AcrobotPlant.ctor.doc_3)
.def(py::init<>(), doc.AcrobotPlant.ctor.doc)
.def("CalcPotentialEnergy", &AcrobotPlant<T>::CalcPotentialEnergy,
doc.AcrobotPlant.DoCalcPotentialEnergy.doc)
.def("CalcKineticEnergy", &AcrobotPlant<T>::CalcKineticEnergy,
Expand All @@ -46,13 +46,13 @@ PYBIND11_MODULE(acrobot, m) {
// TODO(russt): Remove custom bindings once #8096 is resolved.
py::class_<AcrobotInput<T>, BasicVector<T>>(
m, "AcrobotInput", doc.AcrobotInput.doc)
.def(py::init<>(), doc.AcrobotInput.ctor.doc_0args)
.def(py::init<>(), doc.AcrobotInput.ctor.doc)
.def("tau", &AcrobotInput<T>::tau, doc.AcrobotInput.tau.doc)
.def("set_tau", &AcrobotInput<T>::set_tau, doc.AcrobotInput.set_tau.doc);

py::class_<AcrobotParams<T>, BasicVector<T>>(
m, "AcrobotParams", doc.AcrobotParams.doc)
.def(py::init<>(), doc.AcrobotParams.ctor.doc_0args)
.def(py::init<>(), doc.AcrobotParams.ctor.doc)
.def("m1", &AcrobotParams<T>::m1, doc.AcrobotParams.m1.doc)
.def("m2", &AcrobotParams<T>::m2, doc.AcrobotParams.m2.doc)
.def("l1", &AcrobotParams<T>::l1, doc.AcrobotParams.l1.doc)
Expand All @@ -77,7 +77,7 @@ PYBIND11_MODULE(acrobot, m) {

py::class_<AcrobotState<T>, BasicVector<T>>(
m, "AcrobotState", doc.AcrobotState.doc)
.def(py::init<>(), doc.AcrobotState.ctor.doc_0args)
.def(py::init<>(), doc.AcrobotState.ctor.doc)
.def("theta1", &AcrobotState<T>::theta1, doc.AcrobotState.theta1.doc)
.def("theta1dot", &AcrobotState<T>::theta1dot,
doc.AcrobotState.theta1dot.doc)
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/examples/compass_gait_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,12 @@ PYBIND11_MODULE(compass_gait, m) {

py::class_<CompassGait<T>, LeafSystem<T>>(
m, "CompassGait", doc.CompassGait.doc)
.def(py::init<>(), doc.CompassGait.ctor.doc_3);
.def(py::init<>(), doc.CompassGait.ctor.doc);

// TODO(russt): Remove custom bindings once #8096 is resolved.
py::class_<CompassGaitParams<T>, BasicVector<T>>(
m, "CompassGaitParams", doc.CompassGaitParams.doc)
.def(py::init<>(), doc.CompassGaitParams.ctor.doc_0args)
.def(py::init<>(), doc.CompassGaitParams.ctor.doc)
.def("mass_hip", &CompassGaitParams<T>::mass_hip,
doc.CompassGaitParams.mass_hip.doc)
.def("mass_leg", &CompassGaitParams<T>::mass_leg,
Expand Down Expand Up @@ -62,7 +62,7 @@ PYBIND11_MODULE(compass_gait, m) {

py::class_<CompassGaitContinuousState<T>, BasicVector<T>>(
m, "CompassGaitContinuousState", doc.CompassGaitContinuousState.doc)
.def(py::init<>(), doc.CompassGaitContinuousState.ctor.doc_0args)
.def(py::init<>(), doc.CompassGaitContinuousState.ctor.doc)
.def("stance", &CompassGaitContinuousState<T>::stance,
doc.CompassGaitContinuousState.stance.doc)
.def("swing", &CompassGaitContinuousState<T>::swing,
Expand Down
12 changes: 6 additions & 6 deletions bindings/pydrake/examples/manipulation_station_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ PYBIND11_MODULE(manipulation_station, m) {
// creating a geometry::dev::render::DepthCameraProperties struct.
py::class_<ManipulationStation<T>, Diagram<T>>(m, "ManipulationStation")
.def(py::init<double>(), py::arg("time_step") = 0.002,
doc.ManipulationStation.ctor.doc_1args)
doc.ManipulationStation.ctor.doc)
.def("SetupDefaultStation", &ManipulationStation<T>::SetupDefaultStation,
py::arg("collision_model") = IiwaCollisionModel::kNoCollision,
doc.ManipulationStation.SetupDefaultStation.doc)
Expand Down Expand Up @@ -79,7 +79,7 @@ PYBIND11_MODULE(manipulation_station, m) {
const Eigen::Ref<const VectorX<T>>&>(
&ManipulationStation<T>::SetIiwaPosition),
py::arg("station_context"), py::arg("q"),
doc.ManipulationStation.SetIiwaPosition.doc_2args_station_context_q)
doc.ManipulationStation.SetIiwaPosition.doc_2args)
.def("SetIiwaPosition",
[](ManipulationStation<T>* self,
const Eigen::Ref<const VectorX<T>>& q,
Expand All @@ -96,7 +96,7 @@ PYBIND11_MODULE(manipulation_station, m) {
const Eigen::Ref<const VectorX<T>>&>(
&ManipulationStation<T>::SetIiwaVelocity),
py::arg("station_context"), py::arg("v"),
doc.ManipulationStation.SetIiwaVelocity.doc_2args_station_context_v)
doc.ManipulationStation.SetIiwaVelocity.doc_2args)
.def("SetIiwaVelocity",
[](ManipulationStation<T>* self,
const Eigen::Ref<const VectorX<T>>& v,
Expand All @@ -112,7 +112,7 @@ PYBIND11_MODULE(manipulation_station, m) {
overload_cast_explicit<void, systems::Context<T>*, const T&>(
&ManipulationStation<T>::SetWsgPosition),
py::arg("station_context"), py::arg("q"),
doc.ManipulationStation.SetWsgPosition.doc_2args_station_context_q)
doc.ManipulationStation.SetWsgPosition.doc_2args)
.def("SetWsgPosition",
[](ManipulationStation<T>* self, const T& q,
systems::Context<T>* context) {
Expand All @@ -127,7 +127,7 @@ PYBIND11_MODULE(manipulation_station, m) {
overload_cast_explicit<void, systems::Context<T>*, const T&>(
&ManipulationStation<T>::SetWsgVelocity),
py::arg("station_context"), py::arg("v"),
doc.ManipulationStation.SetWsgVelocity.doc_2args_station_context_v)
doc.ManipulationStation.SetWsgVelocity.doc_2args)
.def("SetWsgVelocity",
[](ManipulationStation<T>* self, const T& v,
systems::Context<T>* context) {
Expand Down Expand Up @@ -158,7 +158,7 @@ PYBIND11_MODULE(manipulation_station, m) {
m, "ManipulationStationHardwareInterface")
.def(py::init<const std::vector<std::string>>(),
py::arg("camera_names") = std::vector<std::string>{},
doc.ManipulationStationHardwareInterface.ctor.doc_1args)
doc.ManipulationStationHardwareInterface.ctor.doc)
.def("Connect", &ManipulationStationHardwareInterface::Connect,
py::arg("wait_for_cameras") = true,
doc.ManipulationStationHardwareInterface.Connect.doc)
Expand Down
8 changes: 4 additions & 4 deletions bindings/pydrake/examples/pendulum_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,19 +33,19 @@ PYBIND11_MODULE(pendulum, m) {

py::class_<PendulumPlant<T>, LeafSystem<T>>(
m, "PendulumPlant", doc.PendulumPlant.doc)
.def(py::init<>(), doc.PendulumPlant.ctor.doc_3);
.def(py::init<>(), doc.PendulumPlant.ctor.doc);

// TODO(russt): Remove custom bindings once #8096 is resolved.
py::class_<PendulumInput<T>, BasicVector<T>>(
m, "PendulumInput", doc.PendulumInput.doc)
.def(py::init<>(), doc.PendulumInput.ctor.doc_0args)
.def(py::init<>(), doc.PendulumInput.ctor.doc)
.def("tau", &PendulumInput<T>::tau, doc.PendulumInput.tau.doc)
.def(
"set_tau", &PendulumInput<T>::set_tau, doc.PendulumInput.set_tau.doc);

py::class_<PendulumParams<T>, BasicVector<T>>(
m, "PendulumParams", doc.PendulumParams.doc)
.def(py::init<>(), doc.PendulumParams.ctor.doc_0args)
.def(py::init<>(), doc.PendulumParams.ctor.doc)
.def("mass", &PendulumParams<T>::mass, doc.PendulumParams.mass.doc)
.def("length", &PendulumParams<T>::length, doc.PendulumParams.length.doc)
.def("damping", &PendulumParams<T>::damping,
Expand All @@ -63,7 +63,7 @@ PYBIND11_MODULE(pendulum, m) {

py::class_<PendulumState<T>, BasicVector<T>>(
m, "PendulumState", doc.PendulumState.doc)
.def(py::init<>(), doc.PendulumState.ctor.doc_0args)
.def(py::init<>(), doc.PendulumState.ctor.doc)
.def("theta", &PendulumState<T>::theta, doc.PendulumState.theta.doc)
.def("thetadot", &PendulumState<T>::thetadot,
doc.PendulumState.thetadot.doc)
Expand Down
6 changes: 3 additions & 3 deletions bindings/pydrake/examples/rimless_wheel_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,12 +28,12 @@ PYBIND11_MODULE(rimless_wheel, m) {

py::class_<RimlessWheel<T>, LeafSystem<T>>(
m, "RimlessWheel", doc.RimlessWheel.doc)
.def(py::init<>(), doc.RimlessWheel.ctor.doc_3);
.def(py::init<>(), doc.RimlessWheel.ctor.doc);

// TODO(russt): Remove custom bindings once #8096 is resolved.
py::class_<RimlessWheelParams<T>, BasicVector<T>>(
m, "RimlessWheelParams", doc.RimlessWheelParams.doc)
.def(py::init<>(), doc.RimlessWheelParams.ctor.doc_0args)
.def(py::init<>(), doc.RimlessWheelParams.ctor.doc)
.def(
"mass", &RimlessWheelParams<T>::mass, doc.RimlessWheelParams.mass.doc)
.def("length", &RimlessWheelParams<T>::length,
Expand All @@ -57,7 +57,7 @@ PYBIND11_MODULE(rimless_wheel, m) {

py::class_<RimlessWheelContinuousState<T>, BasicVector<T>>(
m, "RimlessWheelContinuousState", doc.RimlessWheelContinuousState.doc)
.def(py::init<>(), doc.RimlessWheelContinuousState.ctor.doc_0args)
.def(py::init<>(), doc.RimlessWheelContinuousState.ctor.doc)
.def("theta", &RimlessWheelContinuousState<T>::theta,
doc.RimlessWheelContinuousState.theta.doc)
.def("thetadot", &RimlessWheelContinuousState<T>::thetadot,
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/examples/van_der_pol_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@ PYBIND11_MODULE(van_der_pol, m) {

py::class_<VanDerPolOscillator<T>, LeafSystem<T>>(
m, "VanDerPolOscillator", doc.VanDerPolOscillator.doc)
.def(py::init<>(), doc.VanDerPolOscillator.ctor.doc_3);
.def(py::init<>(), doc.VanDerPolOscillator.ctor.doc);
}

} // namespace pydrake
Expand Down
8 changes: 4 additions & 4 deletions bindings/pydrake/geometry_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ void BindIdentifier(py::module m, const std::string& name) {
.format(cls_handle));
return Class{};
}),
cls_doc.ctor.doc_0args)
cls_doc.ctor.doc)
.def("get_value", &Class::get_value, cls_doc.get_value.doc)
.def("is_valid", &Class::is_valid, cls_doc.is_valid.doc)
.def(py::self == py::self)
Expand All @@ -60,7 +60,7 @@ PYBIND11_MODULE(geometry, m) {
py::arg("geometry_id"), doc.SceneGraphInspector.GetFrameId.doc);

py::class_<SceneGraph<T>, LeafSystem<T>>(m, "SceneGraph", doc.SceneGraph.doc)
.def(py::init<>(), doc.SceneGraph.ctor.doc_4)
.def(py::init<>(), doc.SceneGraph.ctor.doc)
.def("get_source_pose_port", &SceneGraph<T>::get_source_pose_port,
py_reference_internal, doc.SceneGraph.get_source_pose_port.doc)
.def("get_pose_bundle_output_port",
Expand Down Expand Up @@ -109,7 +109,7 @@ PYBIND11_MODULE(geometry, m) {

// SignedDistancePair
py::class_<SignedDistancePair<T>>(m, "SignedDistancePair")
.def(py::init<>(), doc.SignedDistancePair.ctor.doc_0args)
.def(py::init<>(), doc.SignedDistancePair.ctor.doc)
.def_readwrite(
"id_A", &SignedDistancePair<T>::id_A, doc.SignedDistancePair.id_A.doc)
.def_readwrite(
Expand All @@ -123,7 +123,7 @@ PYBIND11_MODULE(geometry, m) {

// PenetrationAsPointPair
py::class_<PenetrationAsPointPair<T>>(m, "PenetrationAsPointPair")
.def(py::init<>(), doc.PenetrationAsPointPair.ctor.doc_0args)
.def(py::init<>(), doc.PenetrationAsPointPair.ctor.doc)
.def_readwrite("id_A", &PenetrationAsPointPair<T>::id_A,
doc.PenetrationAsPointPair.id_A.doc)
.def_readwrite("id_B", &PenetrationAsPointPair<T>::id_B,
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/lcm_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -57,7 +57,7 @@ PYBIND11_MODULE(lcm, m) {
using Class = DrakeMockLcm;
py::class_<Class, DrakeLcmInterface>(
m, "DrakeMockLcm", doc.DrakeMockLcm.doc)
.def(py::init<>(), doc.DrakeMockLcm.ctor.doc_0args)
.def(py::init<>(), doc.DrakeMockLcm.ctor.doc)
.def("Subscribe",
[](Class* self, const std::string& channel,
PyHandlerFunction handler) {
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/maliput/api_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,7 +26,7 @@ PYBIND11_MODULE(api, m) {

// TODO(m-chaturvedi) Add doc when typedefs are parsed (#9599)
py::class_<RoadGeometryId>(m, "RoadGeometryId")
.def(py::init<std::string>(), doc.RoadGeometry.ctor.doc_0args)
.def(py::init<std::string>(), doc.RoadGeometry.ctor.doc)
.def("string", &RoadGeometryId::string, py_reference_internal);

py::class_<GeoPosition>(m, "GeoPosition", doc.GeoPositionT.doc)
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/maliput/dragway_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -33,7 +33,7 @@ PYBIND11_MODULE(dragway, m) {
py::arg("road_id"), py::arg("num_lanes"), py::arg("length"),
py::arg("lane_width"), py::arg("shoulder_width"),
py::arg("maximum_height"), py::arg("linear_tolerance"),
py::arg("angular_tolerance"), doc.dragway.RoadGeometry.ctor.doc_8args);
py::arg("angular_tolerance"), doc.dragway.RoadGeometry.ctor.doc);
}

} // namespace pydrake
Expand Down
12 changes: 8 additions & 4 deletions bindings/pydrake/manipulation/planner_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ PYBIND11_MODULE(planner, m) {
return Class{num_positions, num_velocities};
}),
py::arg("num_positions") = 0, py::arg("num_velocities") = 0,
class_doc.ctor.doc_2args)
class_doc.ctor.doc)
.def("get_timestep", &Class::get_timestep, class_doc.get_timestep.doc)
.def("set_timestep", &Class::set_timestep, class_doc.set_timestep.doc)
.def("get_num_positions", &Class::get_num_positions,
Expand Down Expand Up @@ -102,7 +102,9 @@ PYBIND11_MODULE(planner, m) {
q_current, v_current, V, J, parameters);
},
py::arg("q_current"), py::arg("v_current"), py::arg("V"), py::arg("J"),
py::arg("parameters"), doc.DoDifferentialInverseKinematics.doc);
py::arg("parameters"),
doc.DoDifferentialInverseKinematics
.doc_5args_q_current_v_current_V_J_parameters);

m.def("DoDifferentialInverseKinematics",
[](const multibody::MultibodyPlant<double>& robot,
Expand All @@ -116,7 +118,8 @@ PYBIND11_MODULE(planner, m) {
},
py::arg("robot"), py::arg("context"), py::arg("V_WE_desired"),
py::arg("frame_E"), py::arg("parameters"),
doc.DoDifferentialInverseKinematics.doc_4);
doc.DoDifferentialInverseKinematics
.doc_5args_robot_context_V_WE_desired_frame_E_parameters);

m.def("DoDifferentialInverseKinematics",
[](const multibody::MultibodyPlant<double>& robot,
Expand All @@ -130,7 +133,8 @@ PYBIND11_MODULE(planner, m) {
},
py::arg("robot"), py::arg("context"), py::arg("X_WE_desired"),
py::arg("frame_E"), py::arg("parameters"),
doc.DoDifferentialInverseKinematics.doc_5);
doc.DoDifferentialInverseKinematics
.doc_5args_robot_context_X_WE_desired_frame_E_parameters);
}

} // namespace pydrake
Expand Down
2 changes: 1 addition & 1 deletion bindings/pydrake/math_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ PYBIND11_MODULE(math, m) {
py::arg("axis_index"), py::arg("axis_W"), doc.ComputeBasisFromAxis.doc);
py::class_<BarycentricMesh<T>>(m, "BarycentricMesh", doc.BarycentricMesh.doc)
.def(py::init<BarycentricMesh<T>::MeshGrid>(),
doc.BarycentricMesh.ctor.doc_1args)
doc.BarycentricMesh.ctor.doc)
.def("get_input_grid", &BarycentricMesh<T>::get_input_grid,
doc.BarycentricMesh.get_input_grid.doc)
.def("get_input_size", &BarycentricMesh<T>::get_input_size,
Expand Down
Loading

0 comments on commit 5336c31

Please sign in to comment.