Skip to content

Commit

Permalink
Changes for platform.
Browse files Browse the repository at this point in the history
  • Loading branch information
cohnt committed Jan 4, 2024
1 parent 60acf94 commit 2e598ea
Show file tree
Hide file tree
Showing 6 changed files with 50 additions and 52 deletions.
18 changes: 0 additions & 18 deletions bindings/pydrake/geometry/optimization_pybind.h
Original file line number Diff line number Diff line change
Expand Up @@ -27,23 +27,5 @@ geometry::optimization::ConvexSets CloneConvexSets(
return sets;
}

/** Deep-copies the ConvexSet copyable_unique_ptrs in the given list into a
Python-compatible list of ConvexSet unique_ptrs. This is useful to return
Python-natural values out of the C++ API, which would otherwise return the more
complex type. */
std::vector<std::unique_ptr<geometry::optimization::ConvexSet>> CloneConvexSets(
geometry::optimization::ConvexSets sets_in) {
std::vector<std::unique_ptr<geometry::optimization::ConvexSet>> sets_out;
sets_out.reserve(sets_in.size());
for (const auto& set : sets_in) {
if (set == nullptr) {
sets_out.push_back(nullptr);
} else {
sets_out.push_back(set->Clone());
}
}
return sets_out;
}

} // namespace pydrake
} // namespace drake
58 changes: 33 additions & 25 deletions bindings/pydrake/planning/planning_py_trajectory_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -462,31 +462,39 @@ void DefinePlanningTrajectoryOptimization(py::module m) {
py::arg("trajectory"), cls_doc.NormalizeSegmentTimes.doc);
}

m.def(
"PartitionConvexSet",
[](const drake::geometry::optimization::ConvexSet& convex_set,
const std::vector<int>& continuous_revolute_joints,
const double epsilon)
-> std::vector<std::unique_ptr<geometry::optimization::ConvexSet>> {
return CloneConvexSets(PartitionConvexSet(
convex_set, continuous_revolute_joints, epsilon));
},
py::arg("convex_set"), py::arg("continuous_revolute_joints"),
py::arg("epsilon") = 1e-5, py_rvp::take_ownership,
doc.PartitionConvexSet.doc);
m.def(
"PartitionConvexSet",
[](const std::vector<drake::geometry::optimization::ConvexSet*>&
convex_sets,
const std::vector<int>& continuous_revolute_joints,
const double epsilon = 1e-5)
-> std::vector<std::unique_ptr<geometry::optimization::ConvexSet>> {
return CloneConvexSets(PartitionConvexSet(
CloneConvexSets(convex_sets), continuous_revolute_joints, epsilon));
},
py::arg("convex_sets"), py::arg("continuous_revolute_joints"),
py::arg("epsilon") = 1e-5, py_rvp::take_ownership,
doc.PartitionConvexSet.doc);
{
using drake::geometry::optimization::ConvexSet;
m.def(
"PartitionConvexSet",
[](const ConvexSet& convex_set,
const std::vector<int>& continuous_revolute_joints,
const double epsilon) {
std::vector<copyable_unique_ptr<ConvexSet>> copyable_result =
PartitionConvexSet(
convex_set, continuous_revolute_joints, epsilon);
std::vector<std::unique_ptr<ConvexSet>> result(
std::make_move_iterator(copyable_result.begin()),
std::make_move_iterator(copyable_result.end()));
return result;
},
py::arg("convex_set"), py::arg("continuous_revolute_joints"),
py::arg("epsilon") = 1e-5, doc.PartitionConvexSet.doc);
m.def(
"PartitionConvexSet",
[](const std::vector<ConvexSet*>& convex_sets,
const std::vector<int>& continuous_revolute_joints,
const double epsilon = 1e-5) {
std::vector<copyable_unique_ptr<ConvexSet>> copyable_result =
PartitionConvexSet(CloneConvexSets(convex_sets),
continuous_revolute_joints, epsilon);
std::vector<std::unique_ptr<ConvexSet>> result(
std::make_move_iterator(copyable_result.begin()),
std::make_move_iterator(copyable_result.end()));
return result;
},
py::arg("convex_sets"), py::arg("continuous_revolute_joints"),
py::arg("epsilon") = 1e-5, doc.PartitionConvexSet.doc);
}

m.def("GetContinuousRevoluteJointIndices", &GetContinuousRevoluteJointIndices,
py::arg("plant"), doc.GetContinuousRevoluteJointIndices.doc);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,7 @@
GetContinuousRevoluteJointIndices
)
from pydrake.geometry.optimization import (
ConvexSet,
GraphOfConvexSetsOptions,
GraphOfConvexSets,
HPolyhedron,
Expand Down Expand Up @@ -557,7 +558,10 @@ def test_get_continuous_revolute_joint_indices(self):

def test_partition_convex_set(self):
big_convex_set = VPolytope(np.array([[0, 4]]))
PartitionConvexSet(big_convex_set, [0])
out = PartitionConvexSet(big_convex_set, [0])
self.assertEqual(len(out), 2)
self.assertTrue(isinstance(out[0], ConvexSet))

PartitionConvexSet(big_convex_set, [0], 1e-5)
PartitionConvexSet(convex_set=big_convex_set,
continuous_revolute_joints=[0],
Expand Down
10 changes: 5 additions & 5 deletions planning/trajectory_optimization/gcs_trajectory_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -107,11 +107,10 @@ const std::pair<double, double> GetMinimumAndMaximumValueAlongDimension(
return {lower_bound, upper_bound};
}

/** Given a convex set, and a list of indices corresponding to continuous
revolute joints, check whether or not the set satisfies the convexity radius.
Respecting the convexity radius entails that each convex set has a width of
strictly less than π along each dimension corresponding to a continuous
revolute joint. */
/* Helper function to assert that a given list of continuous revolute joint
* indices satisfies the requirements for the constructor to
* GcsTrajectoryOptimization, as well as any static functions that may take in
* such a list. */
void ThrowsForInvalidContinuousJointsList(
int num_positions, const std::vector<int>& continuous_revolute_joints) {
for (int i = 0; i < ssize(continuous_revolute_joints); ++i) {
Expand Down Expand Up @@ -1107,6 +1106,7 @@ ConvexSets PartitionConvexSet(
const ConvexSet& convex_set,
const std::vector<int>& continuous_revolute_joints, const double epsilon) {
DRAKE_THROW_UNLESS(epsilon > 0);
DRAKE_THROW_UNLESS(epsilon < M_PI);
ThrowsForInvalidContinuousJointsList(convex_set.ambient_dimension(),
continuous_revolute_joints);
// Unboundedness will be asserted by
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -569,9 +569,9 @@ num_positions, and unique.
@param epsilon is the ϵ value used for the convexity radius inequality. The
partitioned sets are made by intersecting convex_set with axis-aligned
bounding boxes that respect the convexity radius. These boxes are made to
overlap by ϵ along each dimension, for numerical purposes.
overlap by ϵ radians along each dimension, for numerical purposes.
@return the vector of convex sets that each respect convexity radius.
@throws std::exception if ϵ <= 0.
@throws std::exception if ϵ <= 0 or ϵ >= π.
@throws std::exception if the input convex set is unbounded.
@throws std::exception if continuous_revolute_joints has repeated entries, or if
any entry is outside the interval [0, convex_set.ambient_dimension()). */
Expand All @@ -586,7 +586,7 @@ ambient dimension. Each entry in continuous_revolute_joints must be
non-negative, less than num_positions, and unique.
@throws std::exception unless every ConvexSet in convex_sets has the same
ambient_dimension.
@throws std::exception if ϵ <= 0.
@throws std::exception if ϵ <= 0 or ϵ >= π.
@throws std::exception if continuous_revolute_joints has repeated entries, or if
any entry is outside the interval [0, ambient_dimension). */
geometry::optimization::ConvexSets PartitionConvexSet(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -1510,6 +1510,10 @@ GTEST_TEST(GcsTrajectoryOptimizationTest, PartitionConvexSetAPI) {
// Epsilon must be strictly positive.
EXPECT_THROW(PartitionConvexSet(v, continuous_revolute_joints, 0.0),
std::exception);

// Epsilon must be less than π.
EXPECT_THROW(PartitionConvexSet(v, continuous_revolute_joints, M_PI),
std::exception);
}

GTEST_TEST(GcsTrajectoryOptimizationTest, GetContinuousJoints) {
Expand Down

0 comments on commit 2e598ea

Please sign in to comment.