Skip to content

Commit

Permalink
address some review
Browse files Browse the repository at this point in the history
  • Loading branch information
AlexandreAmice committed Jul 18, 2023
1 parent 35db362 commit d75086d
Show file tree
Hide file tree
Showing 2 changed files with 170 additions and 179 deletions.
118 changes: 56 additions & 62 deletions bindings/pydrake/geometry/geometry_py_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@
#include "drake/bindings/pydrake/pydrake_pybind.h"
#include "drake/common/yaml/yaml_io.h"
#include "drake/geometry/optimization/c_iris_collision_geometry.h"
#include "drake/geometry/optimization/c_iris_separating_plane.h"
#include "drake/geometry/optimization/cartesian_product.h"
#include "drake/geometry/optimization/cspace_free_polytope.h"
#include "drake/geometry/optimization/cspace_free_polytope_base.h"
Expand All @@ -39,48 +38,31 @@ template <typename T>
void DoSeparatingPlaneDeclaration(py::module m, T) {
constexpr auto& doc = pydrake_doc.drake.geometry.optimization;
py::tuple param = GetPyParam<T>();
using BaseClass = geometry::optimization::CSpaceSeparatingPlane<T>;
using Class = geometry::optimization::CSpaceSeparatingPlane<T>;
constexpr auto& base_cls_doc = doc.CSpaceSeparatingPlane;
using CIrisClass = geometry::optimization::CIrisSeparatingPlane<T>;
constexpr auto& ciris_cls_doc = doc.CSpaceSeparatingPlane;
{
auto cls =
DefineTemplateClassWithDefault<BaseClass>(
DefineTemplateClassWithDefault<Class>(
m, "CSpaceSeparatingPlane", param, base_cls_doc.doc)
.def_readonly("a", &BaseClass::a, py_rvp::copy, base_cls_doc.a.doc)
.def_readonly("b", &BaseClass::b, base_cls_doc.b.doc)
// use py_rvp::copy here because numpy.ndarray with dtype=object
// arrays must be copied, and cannot be referenced.
.def_readonly("a", &Class::a, py_rvp::copy, base_cls_doc.a.doc)
.def_readonly("b", &Class::b, base_cls_doc.b.doc)
.def_readonly("positive_side_geometry",
&BaseClass::positive_side_geometry,
&Class::positive_side_geometry,
base_cls_doc.positive_side_geometry.doc)
.def_readonly("negative_side_geometry",
&BaseClass::negative_side_geometry,
&Class::negative_side_geometry,
base_cls_doc.negative_side_geometry.doc)
.def_readonly("expressed_body", &BaseClass::expressed_body,
.def_readonly("expressed_body", &Class::expressed_body,
base_cls_doc.expressed_body.doc)
.def_readonly("decision_variables", &BaseClass::decision_variables,
.def_readonly("plane_degree", &Class::plane_degree)
// use py_rvp::copy here because numpy.ndarray with dtype=object
// arrays must be copied, and cannot be referenced.
.def_readonly("decision_variables", &Class::decision_variables,
py_rvp::copy, base_cls_doc.a.doc);
DefCopyAndDeepCopy(&cls);
AddValueInstantiation<BaseClass>(m);
}
{
auto cls =
DefineTemplateClassWithDefault<CIrisClass>(
m, "CIrisSeparatingPlane", param, ciris_cls_doc.doc)
.def_readonly("a", &CIrisClass::a, py_rvp::copy, base_cls_doc.a.doc)
.def_readonly("b", &CIrisClass::b, base_cls_doc.b.doc)
.def_readonly("positive_side_geometry",
&BaseClass::positive_side_geometry,
base_cls_doc.positive_side_geometry.doc)
.def_readonly("negative_side_geometry",
&BaseClass::negative_side_geometry,
base_cls_doc.negative_side_geometry.doc)
.def_readonly("expressed_body", &BaseClass::expressed_body,
base_cls_doc.expressed_body.doc)
.def_readonly("plane_degree", &BaseClass::plane_degree)
.def_readonly("decision_variables", &BaseClass::decision_variables,
py_rvp::copy, base_cls_doc.a.doc);
DefCopyAndDeepCopy(&cls);
AddValueInstantiation<CIrisClass>(m);
AddValueInstantiation<Class>(m);
}
}

Expand Down Expand Up @@ -780,12 +762,16 @@ void DefineGeometryOptimization(py::module m) {
{
// Definitions for cpsace_free_structs.h/cc
constexpr auto& prog_doc = doc.SeparationCertificateProgramBase;
auto prog_cls =
py::class_<SeparationCertificateProgramBase>(
m, "SeparationCertificateProgramBase", prog_doc.doc)
.def_readonly("prog", &SeparationCertificateProgramBase::prog)
.def_readonly(
"plane_index", &SeparationCertificateProgramBase::plane_index);
auto prog_cls = py::class_<SeparationCertificateProgramBase>(
m, "SeparationCertificateProgramBase", prog_doc.doc)
.def(
"prog",
[](const SeparationCertificateProgramBase* self) {
return self->prog.get();
},
py_rvp::reference_internal)
.def_readonly("plane_index",
&SeparationCertificateProgramBase::plane_index);

constexpr auto& result_doc = doc.SeparationCertificateResultBase;
auto result_cls =
Expand Down Expand Up @@ -878,18 +864,25 @@ void DefineGeometryOptimization(py::module m) {
.def("BinarySearch", &Class::BinarySearch,
py::arg("ignored_collision_pairs"), py::arg("C"), py::arg("d"),
py::arg("s_center"), py::arg("options"), cls_doc.BinarySearch.doc)
.def(
"MakeIsGeometrySeparableProgram",
[](const CspaceFreePolytope* self,
const std::tuple<geometry::GeometryId, geometry::GeometryId>&
geometry_pair,
const Eigen::Ref<const Eigen::MatrixXd>& C,
const Eigen::Ref<const Eigen::VectorXd>& d) {
const SortedPair<geometry::GeometryId> geom_pair{
std::get<0>(geometry_pair), std::get<1>(geometry_pair)};
return self->MakeIsGeometrySeparableProgram(geom_pair, C, d);
},
py::arg("geometry_pair"), py::arg("C"), py::arg("d"),
// .def(
// "MakeIsGeometrySeparableProgram",
// [](const CspaceFreePolytope* self,
// const std::tuple<geometry::GeometryId,
// geometry::GeometryId>&
// geometry_pair,
// const Eigen::Ref<const Eigen::MatrixXd>& C,
// const Eigen::Ref<const Eigen::VectorXd>& d) {
// const SortedPair<geometry::GeometryId> geom_pair{
// std::get<0>(geometry_pair),
// std::get<1>(geometry_pair)};
// return self->MakeIsGeometrySeparableProgram(geom_pair,
// C, d);
// },
// py::arg("geometry_pair"), py::arg("C"), py::arg("d"),
// cls_doc.MakeIsGeometrySeparableProgram.doc)
.def("MakeIsGeometrySeparableProgram",
&Class::MakeIsGeometrySeparableProgram, py::arg("geometry_pair"),
py::arg("C"), py::arg("d"),
cls_doc.MakeIsGeometrySeparableProgram.doc)
.def("SolveSeparationCertificateProgram",
&Class::SolveSeparationCertificateProgram,
Expand All @@ -902,12 +895,12 @@ void DefineGeometryOptimization(py::module m) {
.def("GetSolution", &Class::SeparatingPlaneLagrangians::GetSolution,
py::arg("result"),
cls_doc.SeparatingPlaneLagrangians.GetSolution.doc)
// use py_rvp::copy here because numpy.ndarray with dtype=object arrays
// must be copied, and cannot be referenced.
.def("polytope", &Class::SeparatingPlaneLagrangians::mutable_polytope,
py_rvp::copy)
.def("s_lower", &Class::SeparatingPlaneLagrangians::mutable_s_lower,
py_rvp::copy)
.def("s_upper", &Class::SeparatingPlaneLagrangians::mutable_s_upper,
py_rvp::copy);
.def("s_lower", &Class::SeparatingPlaneLagrangians::mutable_s_lower)
.def("s_upper", &Class::SeparatingPlaneLagrangians::mutable_s_upper);
{
using SepCertClass = Class::SeparationCertificateResult;
py::class_<SepCertClass>(cspace_free_polytope_cls,
Expand All @@ -924,11 +917,15 @@ void DefineGeometryOptimization(py::module m) {
negative_side_rational_lagrangians,
cls_doc.SeparationCertificateResult
.negative_side_rational_lagrangians.doc)
// use py_rvp::copy here because numpy.ndarray with dtype=object
// arrays must be copied, and cannot be referenced.
.def_readonly("a", &SepCertClass::a, py_rvp::copy,
doc.SeparationCertificateResultBase.a.doc)
.def_readonly(
"b", &SepCertClass::b, doc.SeparationCertificateResultBase.b.doc)
.def_readonly("result", &SepCertClass::result)
// use py_rvp::copy here because numpy.ndarray with dtype=object
// arrays must be copied, and cannot be referenced.
.def_readonly("plane_decision_var_vals",
&SepCertClass::plane_decision_var_vals, py_rvp::copy);
}
Expand All @@ -943,16 +940,11 @@ void DefineGeometryOptimization(py::module m) {
.def_readwrite("negative_side_rational_lagrangians",
&Class::SeparationCertificate::negative_side_rational_lagrangians);
{
py::class_<Class::SeparationCertificateProgram>(cspace_free_polytope_cls,
py::class_<Class::SeparationCertificateProgram,
SeparationCertificateProgramBase>(cspace_free_polytope_cls,
"SeparationCertificateProgram",
cls_doc.SeparationCertificateProgram.doc)
.def(py::init<>())
.def(
"prog",
[](const Class::SeparationCertificateProgram* self) {
return self->prog.get();
},
py_rvp::reference_internal)
.def_readonly(
"plane_index", &Class::SeparationCertificateProgram::plane_index)
.def_readonly(
Expand Down Expand Up @@ -999,8 +991,10 @@ void DefineGeometryOptimization(py::module m) {
.def(py::init<>())
.def("C", &Class::SearchResult::C)
.def("d", &Class::SearchResult::d)
// use py_rvp::copy here because numpy.ndarray with dtype=object arrays
// must be copied, and cannot be referenced.
.def("a", &Class::SearchResult::a, py_rvp::copy)
.def("b", &Class::SearchResult::b, py_rvp::copy)
.def("b", &Class::SearchResult::b)
.def("num_iter", &Class::SearchResult::num_iter)
.def("certified_polytope", &Class::SearchResult::certified_polytope);

Expand Down
Loading

0 comments on commit d75086d

Please sign in to comment.