Skip to content

Commit

Permalink
pydrake: Bind some missing multibody plant-related items (RobotLocomo…
Browse files Browse the repository at this point in the history
  • Loading branch information
jwnimmer-tri authored Oct 12, 2020
1 parent 7ce35ee commit 565c6cd
Show file tree
Hide file tree
Showing 7 changed files with 62 additions and 31 deletions.
1 change: 1 addition & 0 deletions bindings/pydrake/multibody/BUILD.bazel
Original file line number Diff line number Diff line change
Expand Up @@ -238,6 +238,7 @@ drake_py_unittest(
"//examples/atlas:models",
"//multibody/benchmarks/acrobot:models",
"//multibody/parsing:process_model_directives_test_models",
"//multibody/parsing:test_models",
],
deps = [
":parsing_py",
Expand Down
16 changes: 11 additions & 5 deletions bindings/pydrake/multibody/parsing_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -29,16 +29,22 @@ PYBIND11_MODULE(parsing, m) {
constexpr auto& cls_doc = doc.PackageMap;
py::class_<Class>(m, "PackageMap", cls_doc.doc)
.def(py::init<>(), cls_doc.ctor.doc)
.def("Add", &Class::Add, cls_doc.Add.doc)
.def("Contains", &Class::Contains, cls_doc.Contains.doc)
.def("Add", &Class::Add, py::arg("package_name"),
py::arg("package_path"), cls_doc.Add.doc)
.def("Contains", &Class::Contains, py::arg("package_name"),
cls_doc.Contains.doc)
.def("size", &Class::size, cls_doc.size.doc)
.def("GetPath", &Class::GetPath, cls_doc.GetPath.doc)
.def("PopulateFromFolder", &Class::PopulateFromFolder,
.def("GetPath", &Class::GetPath, py::arg("package_name"),
cls_doc.GetPath.doc)
.def("AddPackageXml", &Class::AddPackageXml, py::arg("filename"),
cls_doc.AddPackageXml.doc)
.def("PopulateFromFolder", &Class::PopulateFromFolder, py::arg("path"),
cls_doc.PopulateFromFolder.doc)
.def("PopulateFromEnvironment", &Class::PopulateFromEnvironment,
py::arg("environment_variable"),
cls_doc.PopulateFromEnvironment.doc)
.def("PopulateUpstreamToDrake", &Class::PopulateUpstreamToDrake,
cls_doc.PopulateUpstreamToDrake.doc);
py::arg("model_file"), cls_doc.PopulateUpstreamToDrake.doc);
}

// Parser
Expand Down
36 changes: 23 additions & 13 deletions bindings/pydrake/multibody/plant_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -96,6 +96,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def("separation_speed", &Class::separation_speed,
cls_doc.separation_speed.doc)
.def("point_pair", &Class::point_pair, cls_doc.point_pair.doc);
DefCopyAndDeepCopy(&cls);
}

// ContactResults
Expand All @@ -110,6 +111,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
cls_doc.num_point_pair_contacts.doc)
.def("point_pair_contact_info", &Class::point_pair_contact_info,
py::arg("i"), cls_doc.point_pair_contact_info.doc);
DefCopyAndDeepCopy(&cls);
AddValueInstantiation<Class>(m);
}

Expand All @@ -120,12 +122,14 @@ void DoScalarDependentDefinitions(py::module m, T) {
auto cls = DefineTemplateClassWithDefault<Class>(
m, "CoulombFriction", param, cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc_0args)
.def(py::init<const T&, const T&>(), py::arg("static_friction"),
py::arg("dynamic_friction"), cls_doc.ctor.doc_2args)
.def("static_friction", &Class::static_friction,
cls_doc.static_friction.doc)
.def("dynamic_friction", &Class::dynamic_friction,
cls_doc.dynamic_friction.doc);
DefCopyAndDeepCopy(&cls);

AddValueInstantiation<CoulombFriction<T>>(m);

Expand Down Expand Up @@ -1024,6 +1028,7 @@ void DoScalarDependentDefinitions(py::module m, T) {
.def_readwrite("body_index", &Class::body_index, cls_doc.body_index.doc)
.def_readwrite("p_BoBq_B", &Class::p_BoBq_B, cls_doc.p_BoBq_B.doc)
.def_readwrite("F_Bq_W", &Class::F_Bq_W, cls_doc.F_Bq_W.doc);
DefCopyAndDeepCopy(&cls);
AddValueInstantiation<Class>(m);
// Some ports need `Value<std::vector<Class>>`.
AddValueInstantiation<std::vector<Class>>(m);
Expand Down Expand Up @@ -1113,19 +1118,24 @@ PYBIND11_MODULE(plant, m) {
py::keep_alive<3, 1>(),
doc.ConnectContactResultsToDrakeVisualizer.doc_3args);

py::class_<PropellerInfo>(m, "PropellerInfo", doc.PropellerInfo.doc)
.def(py::init<const BodyIndex&, const math::RigidTransform<double>&,
double, double>(),
py::arg("body_index"),
py::arg("X_BP") = math::RigidTransform<double>::Identity(),
py::arg("thrust_ratio") = 1.0, py::arg("moment_ratio") = 0.0)
.def_readwrite("body_index", &PropellerInfo::body_index,
doc.PropellerInfo.body_index.doc)
.def_readwrite("X_BP", &PropellerInfo::X_BP, doc.PropellerInfo.X_BP.doc)
.def_readwrite("thrust_ratio", &PropellerInfo::thrust_ratio,
doc.PropellerInfo.thrust_ratio.doc)
.def_readwrite("moment_ratio", &PropellerInfo::moment_ratio,
doc.PropellerInfo.moment_ratio.doc);
{
using Class = PropellerInfo;
constexpr auto& cls_doc = doc.PropellerInfo;
py::class_<Class> cls(m, "PropellerInfo", cls_doc.doc);
cls // BR
.def(py::init<const BodyIndex&, const math::RigidTransform<double>&,
double, double>(),
py::arg("body_index"),
py::arg("X_BP") = math::RigidTransform<double>::Identity(),
py::arg("thrust_ratio") = 1.0, py::arg("moment_ratio") = 0.0)
.def_readwrite("body_index", &Class::body_index, cls_doc.body_index.doc)
.def_readwrite("X_BP", &Class::X_BP, cls_doc.X_BP.doc)
.def_readwrite(
"thrust_ratio", &Class::thrust_ratio, cls_doc.thrust_ratio.doc)
.def_readwrite(
"moment_ratio", &Class::moment_ratio, cls_doc.moment_ratio.doc);
DefCopyAndDeepCopy(&cls);
}

{
using Class = ContactModel;
Expand Down
16 changes: 9 additions & 7 deletions bindings/pydrake/multibody/test/parsing_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -31,19 +31,21 @@ def test_package_map(self):
model = FindResourceOrThrow(
"drake/examples/atlas/urdf/atlas_minimal_contact.urdf")

# Simple coverage test for Add, Contains, size, GetPath.
dut.Add("root", tmpdir)
# Simple coverage test for Add, Contains, size, GetPath, AddPackageXml.
dut.Add(package_name="root", package_path=tmpdir)
self.assertEqual(dut.size(), 1)
self.assertTrue(dut.Contains("root"))
self.assertEqual(dut.GetPath("root"), tmpdir)
self.assertTrue(dut.Contains(package_name="root"))
self.assertEqual(dut.GetPath(package_name="root"), tmpdir)
dut.AddPackageXml(filename=FindResourceOrThrow(
"drake/multibody/parsing/test/box_package/package.xml"))

# Simple coverage test for Drake paths.
dut.PopulateUpstreamToDrake(model)
dut.PopulateUpstreamToDrake(model_file=model)
self.assertGreater(dut.size(), 1)

# Simple coverage test for folder and environment.
dut.PopulateFromEnvironment('TEST_TMPDIR')
dut.PopulateFromFolder(tmpdir)
dut.PopulateFromEnvironment(environment_variable='TEST_TMPDIR')
dut.PopulateFromFolder(path=tmpdir)

def test_parser_file(self):
"""Calls every combination of arguments for the Parser methods which
Expand Down
12 changes: 12 additions & 0 deletions bindings/pydrake/multibody/test/plant_test.py
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
# -*- coding: utf-8 -*-

import copy
import unittest
import copy

Expand Down Expand Up @@ -536,7 +537,9 @@ def test_spatial_inertia_api(self, T):
@numpy_compare.check_all_types
def test_friction_api(self, T):
CoulombFriction = CoulombFriction_[T]
CoulombFriction()
CoulombFriction(static_friction=0.7, dynamic_friction=0.6)
copy.copy(CoulombFriction())

@numpy_compare.check_all_types
def test_multibody_force_element(self, T):
Expand Down Expand Up @@ -966,6 +969,12 @@ def extract_list_value(port):
# TODO(eric.cousineau): Merge `check_applied_force_input_ports` into
# this test.

@numpy_compare.check_all_types
def test_externally_applied_spatial_force(self, T):
ExternallyAppliedSpatialForce = ExternallyAppliedSpatialForce_[T]
dut = ExternallyAppliedSpatialForce()
copy.copy(dut)

@TemplateSystem.define("AppliedForceTestSystem_")
def AppliedForceTestSystem_(T):

Expand Down Expand Up @@ -1676,10 +1685,12 @@ def test_contact(self, T):
self.assertTrue(isinstance(contact_info.slip_speed(), T))
self.assertIsInstance(
contact_info.point_pair(), PenetrationAsPointPair)
copy.copy(contact_info)

# ContactResults
contact_results = ContactResults()
self.assertTrue(contact_results.num_point_pair_contacts() == 0)
copy.copy(contact_results)

def test_contact_model(self):
plant = MultibodyPlant_[float](0.1)
Expand Down Expand Up @@ -1830,6 +1841,7 @@ def test_propeller(self):
moment_ratio=0.1)
self.assertEqual(info.thrust_ratio, 1.0)
self.assertEqual(info.moment_ratio, 0.1)
copy.copy(info)

prop = Propeller_[float](body_index=BodyIndex(1),
X_BP=RigidTransform_[float](),
Expand Down
6 changes: 3 additions & 3 deletions multibody/parsing/package_map.cc
Original file line number Diff line number Diff line change
Expand Up @@ -220,9 +220,9 @@ void PackageMap::CrawlForPackages(const string& path) {
}
}

void PackageMap::AddPackageXml(const string& package_xml_filename) {
const string package_name = GetPackageName(package_xml_filename);
const string package_path = GetParentDirectory(package_xml_filename);
void PackageMap::AddPackageXml(const string& filename) {
const string package_name = GetPackageName(filename);
const string package_path = GetParentDirectory(filename);
Add(package_name, package_path);
}

Expand Down
6 changes: 3 additions & 3 deletions multibody/parsing/package_map.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,9 @@ class PackageMap {
const std::string& GetPath(const std::string& package_name) const;

/// Adds an entry into this PackageMap for the given `package.xml` filename.
/// Throws if @p package_xml_filename does not exist or its embedded name
/// already exists in this map.
void AddPackageXml(const std::string& package_xml_filename);
/// Throws if @p filename does not exist or its embedded name already exists
/// in this map.
void AddPackageXml(const std::string& filename);

/// Crawls down the directory tree starting at @p path searching for
/// directories containing the file `package.xml`. For each of these
Expand Down

0 comments on commit 565c6cd

Please sign in to comment.