Skip to content

Commit

Permalink
Adds bindings for Hyperrectangle. (RobotLocomotion#20690)
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexandreAmice authored Dec 19, 2023
1 parent e855fbc commit a134958
Show file tree
Hide file tree
Showing 3 changed files with 71 additions and 1 deletion.
25 changes: 25 additions & 0 deletions bindings/pydrake/geometry/geometry_py_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include "drake/geometry/optimization/graph_of_convex_sets.h"
#include "drake/geometry/optimization/hpolyhedron.h"
#include "drake/geometry/optimization/hyperellipsoid.h"
#include "drake/geometry/optimization/hyperrectangle.h"
#include "drake/geometry/optimization/intersection.h"
#include "drake/geometry/optimization/iris.h"
#include "drake/geometry/optimization/minkowski_sum.h"
Expand Down Expand Up @@ -324,6 +325,30 @@ void DefineGeometryOptimization(py::module m) {
}));
}

// Hyperrectangle
{
const auto& cls_doc = doc.Hyperrectangle;
py::class_<Hyperrectangle, ConvexSet>(m, "Hyperrectangle", cls_doc.doc)
.def(py::init<>(), cls_doc.ctor.doc_0args)
.def(py::init<const Eigen::Ref<const Eigen::VectorXd>&,
const Eigen::Ref<const Eigen::VectorXd>&>(),
py::arg("lb"), py::arg("ub"), cls_doc.ctor.doc_2args)
.def("lb", &Hyperrectangle::lb, cls_doc.lb.doc)
.def("ub", &Hyperrectangle::ub, cls_doc.ub.doc)
.def("UniformSample", &Hyperrectangle::UniformSample,
py::arg("generator"), cls_doc.UniformSample.doc)
.def("Center", &Hyperrectangle::Center, cls_doc.Center.doc)
.def("MakeHPolyhedron", &Hyperrectangle::MakeHPolyhedron,
cls_doc.MakeHPolyhedron.doc)
.def(py::pickle(
[](const Hyperrectangle& self) {
return std::make_pair(self.lb(), self.ub());
},
[](std::pair<Eigen::VectorXd, Eigen::VectorXd> args) {
return Hyperrectangle(std::get<0>(args), std::get<1>(args));
}));
}

// Intersection
{
const auto& cls_doc = doc.Intersection;
Expand Down
46 changes: 45 additions & 1 deletion bindings/pydrake/geometry/test/optimization_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ class TestGeometryOptimization(unittest.TestCase):
def __init__(self, *args, **kwargs):
super().__init__(*args, **kwargs)
self.A = np.eye(3)
self.b = [1.0, 1.0, 1.0]
self.b = np.array([1.0, 1.0, 1.0])
self.prog = MathematicalProgram()
self.x = self.prog.NewContinuousVariables(3, "x")
self.t = self.prog.NewContinuousVariables(1, "t")[0]
Expand Down Expand Up @@ -335,6 +335,50 @@ def test_hyper_ellipsoid(self):
points=points)
mut.Hyperellipsoid(ellipsoid=mut.AffineBall.MakeUnitBall(dim=1))

def test_hyperrectangle(self):
mut.Hyperrectangle()
rect = mut.Hyperrectangle(lb=-self.b, ub=self.b)

# Methods inherited from ConvexSet
self.assertEqual(rect.ambient_dimension(), self.b.shape[0])
self.assertTrue(rect.IntersectsWith(rect))
self.assertTrue(rect.IsBounded())
self.assertFalse(rect.IsEmpty())
self.assertTrue(rect.MaybeGetPoint() is None)
point = rect.MaybeGetFeasiblePoint()
self.assertTrue(point is not None)
self.assertTrue(rect.PointInSet(x=point, tol=0.0))
new_vars, new_constraints = rect.AddPointInSetConstraints(
self.prog, self.x)
self.assertEqual(new_vars.size, 0)
self.assertGreater(len(new_constraints), 0)
constraints = rect.AddPointInNonnegativeScalingConstraints(
prog=self.prog, x=self.x, t=self.t)
self.assertGreaterEqual(len(constraints), 2)
self.assertIsInstance(constraints[0], Binding[Constraint])
constraints = rect.AddPointInNonnegativeScalingConstraints(
prog=self.prog, A=self.Ay, b=self.by, c=self.cz, d=self.dz,
x=self.y, t=self.z)
self.assertGreaterEqual(len(constraints), 2)
self.assertIsInstance(constraints[0], Binding[Constraint])
shape, pose = rect.ToShapeWithPose()
self.assertTrue(isinstance(shape, Box))
np.testing.assert_array_equal(pose.translation(),
np.zeros_like(self.b))

# Methods specific to Hyperrectangle
np.testing.assert_array_equal(rect.lb(), -self.b)
np.testing.assert_array_equal(rect.ub(), self.b)
np.testing.assert_array_equal(rect.Center(), np.zeros_like(self.b))
generator = RandomGenerator()
sample = rect.UniformSample(generator=generator)
self.assertEqual(sample.shape, (self.b.shape[0],))
hpoly = rect.MakeHPolyhedron()
box = mut.HPolyhedron.MakeBox(rect.lb(), rect.ub())
np.testing.assert_array_equal(hpoly.A(), box.A())
np.testing.assert_array_equal(hpoly.b(), box.b())
assert_pickle(self, rect, lambda S: np.vstack((S.lb(), S.ub())))

def test_minkowski_sum(self):
mut.MinkowskiSum()
point = mut.Point(np.array([11.1, 12.2, 13.3]))
Expand Down
1 change: 1 addition & 0 deletions geometry/optimization/hyperrectangle.h
Original file line number Diff line number Diff line change
Expand Up @@ -20,6 +20,7 @@ class Hyperrectangle final : public ConvexSet {
public:
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Hyperrectangle)

/** Constructs a default (zero-dimensional, nonempty) hyperrectangle. */
Hyperrectangle();

/** Constructs a hyperrectangle from its lower and upper bounds.
Expand Down

0 comments on commit a134958

Please sign in to comment.