-
Notifications
You must be signed in to change notification settings - Fork 1.3k
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
This adds the minimal functionality to be useful. I will follow-up with more PRs to fill in the "not implemented yet" blocks as needed.
- Loading branch information
1 parent
ff288a1
commit 88dae28
Showing
6 changed files
with
402 additions
and
0 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,190 @@ | ||
#include "drake/geometry/optimization/spectrahedron.h" | ||
|
||
#include <limits> | ||
#include <memory> | ||
|
||
#include <fmt/format.h> | ||
|
||
#include "drake/solvers/get_program_type.h" | ||
|
||
namespace drake { | ||
namespace geometry { | ||
namespace optimization { | ||
|
||
using Eigen::MatrixXd; | ||
using Eigen::VectorXd; | ||
using solvers::Binding; | ||
using solvers::Constraint; | ||
using solvers::MathematicalProgram; | ||
using solvers::ProgramAttribute; | ||
using solvers::ProgramAttributes; | ||
using solvers::VectorXDecisionVariable; | ||
using symbolic::Variable; | ||
|
||
namespace { | ||
|
||
// TODO(russt): This can be replaced by vars(indices) once we have Eigen 3.4. | ||
VectorXDecisionVariable GetVariablesByIndex( | ||
const Eigen::Ref<const VectorXDecisionVariable>& vars, | ||
std::vector<int> indices) { | ||
VectorXDecisionVariable new_vars(indices.size()); | ||
for (int i = 0; i < static_cast<int>(indices.size()); ++i) { | ||
new_vars[i] = vars[indices[i]]; | ||
} | ||
return new_vars; | ||
} | ||
|
||
} // namespace | ||
|
||
const solvers::ProgramAttributes Spectrahedron::supported_attributes_ = { | ||
ProgramAttribute::kLinearCost, ProgramAttribute::kLinearConstraint, | ||
ProgramAttribute::kLinearEqualityConstraint, | ||
ProgramAttribute::kPositiveSemidefiniteConstraint}; | ||
|
||
Spectrahedron::Spectrahedron() | ||
: ConvexSet(&ConvexSetCloner<Spectrahedron>, 0) {} | ||
|
||
Spectrahedron::Spectrahedron(const MathematicalProgram& prog) | ||
: ConvexSet(&ConvexSetCloner<Spectrahedron>, prog.num_vars()) { | ||
for (const auto& attr : prog.required_capabilities()) { | ||
if (supported_attributes().count(attr) < 1) { | ||
throw std::runtime_error( | ||
fmt::format("Spectrahedron does not support MathematicalPrograms " | ||
"that require ProgramAttribute {}. If that attribute is " | ||
"convex, it might be possible to add that support.", | ||
attr)); | ||
} | ||
} | ||
sdp_ = prog.Clone(); | ||
// Remove any objective functions. | ||
for (const auto& binding : sdp_->GetAllCosts()) { | ||
sdp_->RemoveCost(binding); | ||
} | ||
} | ||
|
||
Spectrahedron::~Spectrahedron() = default; | ||
|
||
bool Spectrahedron::DoIsBounded() const { | ||
throw std::runtime_error( | ||
"Spectrahedron::IsBounded() is not implemented yet."); | ||
} | ||
|
||
bool Spectrahedron::DoPointInSet(const Eigen::Ref<const VectorXd>& x, | ||
double tol) const { | ||
return sdp_->CheckSatisfied(sdp_->GetAllConstraints(), x, tol); | ||
} | ||
|
||
void Spectrahedron::DoAddPointInSetConstraints( | ||
MathematicalProgram* prog, | ||
const Eigen::Ref<const VectorXDecisionVariable>& x) const { | ||
DRAKE_DEMAND(x.size() == sdp_->num_vars()); | ||
for (const auto& binding : sdp_->GetAllConstraints()) { | ||
prog->AddConstraint( | ||
binding.evaluator(), | ||
GetVariablesByIndex( | ||
x, sdp_->FindDecisionVariableIndices(binding.variables()))); | ||
} | ||
} | ||
|
||
std::vector<Binding<Constraint>> | ||
Spectrahedron::DoAddPointInNonnegativeScalingConstraints( | ||
MathematicalProgram* prog, | ||
const Eigen::Ref<const VectorXDecisionVariable>& x, | ||
const Variable& t) const { | ||
DRAKE_DEMAND(x.size() == sdp_->num_vars()); | ||
std::vector<Binding<Constraint>> constraints; | ||
const double kInf = std::numeric_limits<double>::infinity(); | ||
|
||
// TODO(russt): Support SparseMatrix constraints. | ||
for (const auto& binding : sdp_->bounding_box_constraints()) { | ||
// t*lb ≤ x ≤ t*ub, implemented as | ||
// [I,-lb]*[x;t] ≥ 0, [I,-ub]*[x;t] ≤ 0. | ||
VectorXDecisionVariable vars(binding.evaluator()->num_vars()+1); | ||
vars << GetVariablesByIndex( | ||
x, sdp_->FindDecisionVariableIndices(binding.variables())), | ||
t; | ||
MatrixXd Ab = MatrixXd::Identity(binding.evaluator()->num_constraints(), | ||
binding.evaluator()->num_vars() + 1); | ||
// TODO(russt): Handle individual elements that are infinite. | ||
if (binding.evaluator()->lower_bound().array().isFinite().any()) { | ||
Ab.rightCols<1>() = -binding.evaluator()->lower_bound(); | ||
prog->AddLinearConstraint(Ab, 0, kInf, vars); | ||
} | ||
if (binding.evaluator()->upper_bound().array().isFinite().any()) { | ||
Ab.rightCols<1>() = -binding.evaluator()->upper_bound(); | ||
prog->AddLinearConstraint(Ab, -kInf, 0, vars); | ||
} | ||
} | ||
for (const auto& binding : sdp_->linear_equality_constraints()) { | ||
// Ax = t*b, implemented as | ||
// [A,-lb]*[x;t] == 0. | ||
VectorXDecisionVariable vars(binding.evaluator()->num_vars()+1); | ||
vars << GetVariablesByIndex( | ||
x, sdp_->FindDecisionVariableIndices(binding.variables())), | ||
t; | ||
MatrixXd Ab(binding.evaluator()->num_constraints(), | ||
binding.evaluator()->num_vars() + 1); | ||
Ab.leftCols(binding.evaluator()->num_vars()) = | ||
binding.evaluator()->GetDenseA(); | ||
Ab.rightCols<1>() = -binding.evaluator()->lower_bound(); | ||
prog->AddLinearConstraint(Ab, 0, 0, vars); | ||
} | ||
for (const auto& binding : sdp_->linear_constraints()) { | ||
// t*lb <= Ax = t*ub, implemented as | ||
// [A,-lb]*[x;t] ≥ 0, [A,-ub]*[x;t] ≤ 0. | ||
VectorXDecisionVariable vars(binding.evaluator()->num_vars()+1); | ||
vars << GetVariablesByIndex( | ||
x, sdp_->FindDecisionVariableIndices(binding.variables())), | ||
t; | ||
MatrixXd Ab(binding.evaluator()->num_constraints(), | ||
binding.evaluator()->num_vars() + 1); | ||
Ab.leftCols(binding.evaluator()->num_vars()) = | ||
binding.evaluator()->GetDenseA(); | ||
if (binding.evaluator()->lower_bound().array().isFinite().any()) { | ||
Ab.rightCols<1>() = -binding.evaluator()->lower_bound(); | ||
prog->AddLinearConstraint(Ab, 0, kInf, vars); | ||
} | ||
if (binding.evaluator()->upper_bound().array().isFinite().any()) { | ||
Ab.rightCols<1>() = -binding.evaluator()->upper_bound(); | ||
prog->AddLinearConstraint(Ab, -kInf, 0, vars); | ||
} | ||
} | ||
for (const auto& binding : sdp_->positive_semidefinite_constraints()) { | ||
// These constraints get added without modification -- a non-negative | ||
// scaling of the PSD cone is just the PSD cone. | ||
constraints.emplace_back(prog->AddConstraint( | ||
binding.evaluator(), | ||
Eigen::Map<MatrixX<Variable>>( | ||
GetVariablesByIndex( | ||
x, sdp_->FindDecisionVariableIndices(binding.variables())) | ||
.data(), | ||
binding.evaluator()->matrix_rows(), | ||
binding.evaluator()->matrix_rows()))); | ||
} | ||
return constraints; | ||
} | ||
|
||
std::vector<Binding<Constraint>> | ||
Spectrahedron::DoAddPointInNonnegativeScalingConstraints( | ||
MathematicalProgram* prog, const Eigen::Ref<const MatrixXd>& A, | ||
const Eigen::Ref<const VectorXd>& b, const Eigen::Ref<const VectorXd>& c, | ||
double d, const Eigen::Ref<const VectorXDecisionVariable>& x, | ||
const Eigen::Ref<const VectorXDecisionVariable>& t) const { | ||
unused(prog, A, b, c, d, x, t); | ||
throw std::runtime_error( | ||
"Spectrahedron::PointInNonnegativeScalingConstraints() is not " | ||
"implemented yet for the case where A, b, c, and d are passed in as " | ||
"arguments."); | ||
} | ||
|
||
std::pair<std::unique_ptr<Shape>, math::RigidTransformd> | ||
Spectrahedron::DoToShapeWithPose() const { | ||
// I could potentially visualize the 2x2 case in three dimensions (as a mesh | ||
// if nothing else). | ||
throw std::runtime_error( | ||
"ToShapeWithPose is not supported by Spectrahedron."); | ||
} | ||
|
||
} // namespace optimization | ||
} // namespace geometry | ||
} // namespace drake |
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -0,0 +1,80 @@ | ||
#pragma once | ||
|
||
#include <memory> | ||
#include <optional> | ||
#include <utility> | ||
#include <vector> | ||
|
||
#include "drake/geometry/optimization/convex_set.h" | ||
#include "drake/solvers/mathematical_program.h" | ||
|
||
namespace drake { | ||
namespace geometry { | ||
namespace optimization { | ||
|
||
/** Implements a spectrahedron (the feasible set of a semidefinite program). | ||
The ambient dimension of the set is N(N+1)/2; the number of variables required | ||
to describe the N-by-N semidefinite matrix. | ||
@ingroup geometry_optimization | ||
*/ | ||
class Spectrahedron final : public ConvexSet { | ||
public: | ||
DRAKE_DEFAULT_COPY_AND_MOVE_AND_ASSIGN(Spectrahedron) | ||
|
||
/** Default constructor (which constructs the empty set). */ | ||
Spectrahedron(); | ||
|
||
/** Constructs the spectrahedron from a MathematicalProgram. | ||
@throws std::exception if @p prog.required_capabilities() is not a subset of | ||
supported_attributes(). */ | ||
explicit Spectrahedron(const solvers::MathematicalProgram& prog); | ||
|
||
~Spectrahedron() final; | ||
|
||
/** Returns the list of solvers::ProgramAttributes supported by this class. */ | ||
static const solvers::ProgramAttributes& supported_attributes() { | ||
return supported_attributes_; | ||
} | ||
|
||
// TODO(russt): Add PointInSet(MatrixXd X, double tol) overload, which will | ||
// only work in the case where the ambient_dimension is ONLY symmetric | ||
// matrices. | ||
|
||
private: | ||
bool DoIsBounded() const final; | ||
|
||
bool DoPointInSet(const Eigen::Ref<const Eigen::VectorXd>& x, | ||
double tol) const final; | ||
|
||
void DoAddPointInSetConstraints( | ||
solvers::MathematicalProgram* prog, | ||
const Eigen::Ref<const solvers::VectorXDecisionVariable>& vars) | ||
const final; | ||
|
||
std::vector<solvers::Binding<solvers::Constraint>> | ||
DoAddPointInNonnegativeScalingConstraints( | ||
solvers::MathematicalProgram* prog, | ||
const Eigen::Ref<const solvers::VectorXDecisionVariable>& x, | ||
const symbolic::Variable& t) const final; | ||
|
||
std::vector<solvers::Binding<solvers::Constraint>> | ||
DoAddPointInNonnegativeScalingConstraints( | ||
solvers::MathematicalProgram* prog, | ||
const Eigen::Ref<const Eigen::MatrixXd>& A, | ||
const Eigen::Ref<const Eigen::VectorXd>& b, | ||
const Eigen::Ref<const Eigen::VectorXd>& c, double d, | ||
const Eigen::Ref<const solvers::VectorXDecisionVariable>& x, | ||
const Eigen::Ref<const solvers::VectorXDecisionVariable>& t) const final; | ||
|
||
std::pair<std::unique_ptr<Shape>, math::RigidTransformd> DoToShapeWithPose() | ||
const final; | ||
|
||
copyable_unique_ptr<solvers::MathematicalProgram> sdp_{}; | ||
|
||
static const solvers::ProgramAttributes supported_attributes_; | ||
}; | ||
|
||
} // namespace optimization | ||
} // namespace geometry | ||
} // namespace drake |
Oops, something went wrong.