Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Bind copyability of schema types #16261

Merged
merged 1 commit into from
Dec 20, 2021
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
42 changes: 34 additions & 8 deletions bindings/pydrake/common/schema_py.cc
Original file line number Diff line number Diff line change
Expand Up @@ -39,42 +39,54 @@ PYBIND11_MODULE(schema, m) {
{
using Class = Deterministic;
constexpr auto& cls_doc = doc.Deterministic;
py::class_<Class, Distribution>(m, "Deterministic", cls_doc.doc)
py::class_<Class, Distribution> cls(m, "Deterministic", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<double>(), py::arg("value"), cls_doc.ctor.doc)
.def_readwrite("value", &Class::value, cls_doc.value.doc);
DefCopyAndDeepCopy(&cls);
}

{
using Class = Gaussian;
constexpr auto& cls_doc = doc.Gaussian;
py::class_<Class, Distribution>(m, "Gaussian", cls_doc.doc)
py::class_<Class, Distribution> cls(m, "Gaussian", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<double, double>(), py::arg("mean"), py::arg("stddev"),
cls_doc.ctor.doc)
.def_readwrite("mean", &Class::mean, cls_doc.mean.doc)
.def_readwrite("stddev", &Class::stddev, cls_doc.stddev.doc);
DefCopyAndDeepCopy(&cls);
}

{
using Class = Uniform;
constexpr auto& cls_doc = doc.Uniform;
py::class_<Class, Distribution>(m, "Uniform", cls_doc.doc)
py::class_<Class, Distribution> cls(m, "Uniform", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<double, double>(), py::arg("min"), py::arg("max"),
cls_doc.ctor.doc)
.def_readwrite("min", &Class::min, cls_doc.min.doc)
.def_readwrite("max", &Class::max, cls_doc.max.doc);
DefCopyAndDeepCopy(&cls);
}

{
using Class = UniformDiscrete;
constexpr auto& cls_doc = doc.UniformDiscrete;
py::class_<Class, Distribution>(m, "UniformDiscrete", cls_doc.doc)
py::class_<Class, Distribution> cls(m, "UniformDiscrete", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<std::vector<double>>(), py::arg("values"),
cls_doc.ctor.doc)
.def_readwrite("values", &Class::values, cls_doc.values.doc);
DefCopyAndDeepCopy(&cls);
}

{
Expand Down Expand Up @@ -126,38 +138,48 @@ PYBIND11_MODULE(schema, m) {
constexpr int size = Eigen::Dynamic;
using Class = DeterministicVector<size>;
constexpr auto& cls_doc = doc.DeterministicVector;
py::class_<Class, DistributionVector>(
m, "DeterministicVectorX", cls_doc.doc)
py::class_<Class, DistributionVector> cls(
m, "DeterministicVectorX", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<const drake::Vector<double, size>&>(), py::arg("value"),
cls_doc.ctor.doc)
.def_readwrite("value", &Class::value, cls_doc.value.doc);
DefCopyAndDeepCopy(&cls);
}

{
constexpr int size = Eigen::Dynamic;
using Class = GaussianVector<size>;
constexpr auto& cls_doc = doc.GaussianVector;
py::class_<Class, DistributionVector>(m, "GaussianVectorX", cls_doc.doc)
py::class_<Class, DistributionVector> cls(
m, "GaussianVectorX", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<const drake::Vector<double, size>&,
const drake::VectorX<double>&>(),
py::arg("mean"), py::arg("stddev"), cls_doc.ctor.doc)
.def_readwrite("mean", &Class::mean, cls_doc.mean.doc)
.def_readwrite("stddev", &Class::stddev, cls_doc.stddev.doc);
DefCopyAndDeepCopy(&cls);
}

{
constexpr int size = Eigen::Dynamic;
using Class = UniformVector<size>;
constexpr auto& cls_doc = doc.UniformVector;
py::class_<Class, DistributionVector>(m, "UniformVectorX", cls_doc.doc)
py::class_<Class, DistributionVector> cls(m, "UniformVectorX", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<const drake::Vector<double, size>&,
const drake::Vector<double, size>&>(),
py::arg("min"), py::arg("max"), cls_doc.ctor.doc)
.def_readwrite("min", &Class::min, cls_doc.min.doc)
.def_readwrite("max", &Class::max, cls_doc.max.doc);
DefCopyAndDeepCopy(&cls);
}

{
Expand Down Expand Up @@ -187,6 +209,7 @@ PYBIND11_MODULE(schema, m) {
py::class_<Class> cls(m, "Rotation", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc_0args)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<const math::RotationMatrixd&>(), cls_doc.ctor.doc_1args)
.def(py::init<const math::RollPitchYawd&>(), cls_doc.ctor.doc_1args)
.def("IsDeterministic", &Class::IsDeterministic,
Expand All @@ -199,6 +222,7 @@ PYBIND11_MODULE(schema, m) {
// TODO(jwnimmer-tri) Bind the .value field.
// In the meantime, a work-around for read access is to call ToSymbolic or
// GetDeterministicValue.
DefCopyAndDeepCopy(&cls);
}

// Bindings for transform.h.
Expand All @@ -209,6 +233,7 @@ PYBIND11_MODULE(schema, m) {
py::class_<Class> cls(m, "Transform", cls_doc.doc);
cls // BR
.def(py::init<>(), cls_doc.ctor.doc_0args)
.def(py::init<const Class&>(), py::arg("other"))
.def(py::init<const math::RigidTransformd&>(), cls_doc.ctor.doc_1args)
.def("set_rotation_rpy_deg", &Class::set_rotation_rpy_deg,
py::arg("rpy_deg"), cls_doc.set_rotation_rpy_deg.doc)
Expand All @@ -223,6 +248,7 @@ PYBIND11_MODULE(schema, m) {
// TODO(jwnimmer-tri) Bind the .translation and .rotation fields.
// In the meantime, a work-around for read access is to call ToSymbolic or
// GetDeterministicValue.
DefCopyAndDeepCopy(&cls);
}
}

Expand Down
19 changes: 16 additions & 3 deletions bindings/pydrake/common/test/schema_test.py
Original file line number Diff line number Diff line change
@@ -1,3 +1,4 @@
import copy
import unittest

from pydrake.common import RandomGenerator
Expand All @@ -8,8 +9,13 @@
class TestSchema(unittest.TestCase):

def _check_distribution(self, dut):
"""Confirms that subclasses of Distribution bind the base methods."""
"""Confirms that a subclass instance of Distribution
* binds the base methods, and
* supports copy/deepcopy (even though the superclass does not).
"""
self.assertIsInstance(dut, mut.Distribution)
copy.copy(dut)
copy.deepcopy(dut)
dut.Sample(generator=RandomGenerator())
dut.Mean()
dut.ToSymbolic()
Expand Down Expand Up @@ -59,10 +65,13 @@ def test_distribution_variant(self):
mut.GetDeterministicValue(var=item)

def _check_distribution_vector(self, dut):
"""Confirms that subclasses of DistributionVector bind the base
methods.
"""Confirms that a subclass instance of DistributionVector
* binds the base methods, and
* supports copy/deepcopy (even though the superclass does not).
"""
self.assertIsInstance(dut, mut.DistributionVector)
copy.copy(dut)
copy.deepcopy(dut)
dut.Sample(generator=RandomGenerator())
dut.Mean()
dut.ToSymbolic()
Expand Down Expand Up @@ -105,6 +114,8 @@ def test_rotation(self):
mut.Rotation()
mut.Rotation(pydrake.math.RotationMatrix())
dut = mut.Rotation(pydrake.math.RollPitchYaw([0.0, 0.0, 0.0]))
copy.copy(dut)
copy.deepcopy(dut)
dut.IsDeterministic()
dut.GetDeterministicValue()
dut.ToSymbolic()
Expand All @@ -113,6 +124,8 @@ def test_rotation(self):
def test_transform(self):
mut.Transform()
dut = mut.Transform(pydrake.math.RigidTransform())
copy.copy(dut)
copy.deepcopy(dut)
dut.set_rotation_rpy_deg([0.1, 0.2, 0.3])
dut.IsDeterministic()
dut.GetDeterministicValue()
Expand Down