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

Add Expression Costs and Formula Constraints to Subgraphs in GcsTrajectoryOptimization #22091

Merged
Merged
Show file tree
Hide file tree
Changes from 11 commits
Commits
Show all changes
25 commits
Select commit Hold shift + click to select a range
58a577d
Create methods to get the placeholder variables for vertices and edge…
cohnt Oct 28, 2024
443e329
I think this is what the substitution should look like.
cohnt Oct 28, 2024
182267e
Fix: costs should be symbolic::Expression, and constraint should be s…
cohnt Oct 28, 2024
773817e
Populate the AddCost and AddConstraint methods.
cohnt Oct 28, 2024
efc6446
Actually construct the placeholder variables.
cohnt Oct 28, 2024
6b8786d
Fix issues with parsing costs. Remove a segfault (due to not reshapin…
cohnt Oct 28, 2024
5f30dba
Test subgraph vertex costs and constraints.
cohnt Oct 28, 2024
47fd5a2
Identify the bug.
cohnt Oct 29, 2024
4c4b324
Fix the bug.
cohnt Oct 29, 2024
9661d89
Test subgraph edge costs and constraints.
cohnt Oct 29, 2024
bb92738
Update tolerances for non-commerical solvers.
cohnt Oct 29, 2024
fa19877
Use duration instead of time throughout. Make variable types more rea…
cohnt Oct 30, 2024
ab9dc45
Update documentation per Russ' suggestion.
cohnt Oct 30, 2024
88c308f
Use duration instead of time internally.
cohnt Oct 30, 2024
ba661df
Fix documentation.
cohnt Nov 5, 2024
f5f44be
Merge master.
cohnt Nov 6, 2024
35602ae
Use templates for the variable substitution methods.
cohnt Nov 8, 2024
e6fd1fe
Another name idea.
cohnt Nov 8, 2024
a40955d
fixup templates
RussTedrake Nov 8, 2024
e561c84
Better code reuse by adding a generic method to substitute variables.
cohnt Nov 8, 2024
1edcd52
Further documentation improvement and error message checking.
cohnt Nov 10, 2024
138a10e
Merge remote-tracking branch 'upstream/master' into gcstrajopt-generi…
cohnt Nov 11, 2024
ee17643
Remove the templated conditional.
cohnt Nov 11, 2024
8bd12ca
Nicer error messages specifically for mixing up edge and vertex place…
cohnt Nov 11, 2024
9046861
Documentation fixes.
cohnt Nov 11, 2024
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
6 changes: 5 additions & 1 deletion geometry/optimization/graph_of_convex_sets.cc
Original file line number Diff line number Diff line change
Expand Up @@ -992,12 +992,14 @@ void GraphOfConvexSets::AddPerspectiveConstraint(
a[0] = -lc->upper_bound()[i];
a.tail(A.cols()) = A.row(i);
prog->AddLinearConstraint(a, -inf, 0, vars);
} else if (lc->lower_bound()[i] > 0) {
} else if (lc->upper_bound()[i] < 0) {
// If the upper bound is -inf, we cannot take the perspective of such
// a constraint, so we throw an error.
throw std::runtime_error(
"Cannot take the perspective of a trivially-infeasible linear "
"constraint of the form x <= -inf.");
} else {
// Do nothing for the constraint x <= inf.
}
}
}
Expand Down Expand Up @@ -1029,6 +1031,8 @@ void GraphOfConvexSets::AddPerspectiveConstraint(
throw std::runtime_error(
"Cannot take the perspective of a trivially-infeasible linear "
"constraint of the form x >= +inf.");
} else {
// Do nothing for the constraint x >= -inf.
}
}
}
Expand Down
76 changes: 67 additions & 9 deletions geometry/optimization/test/graph_of_convex_sets_test.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1735,24 +1735,82 @@ TEST_F(ThreeBoxes, LinearConstraint3) {
TEST_F(ThreeBoxes, InvalidLinearConstraintUpper) {
const Matrix2d A = Matrix2d::Identity();
const Vector2d b{.5, .3};
const Vector2d c_good{1.0, kInf};
const Vector2d c_bad{1.0, -kInf};

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b, c_good), e_on_->xv()));
// b ≤ e_on_->xv() ≤ c_good. No error on the upper bound -- the infinity
// component is trivially feasible.
DRAKE_EXPECT_NO_THROW(g_.SolveShortestPath(*source_, *target_, options_));

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b, c_bad), e_on_->xv()));
// b ≤ e_on_->xv() ≤ c_bad. We can't take the perspective of the
// trivially-infeasible constraint, so solving should throw an error.
DRAKE_EXPECT_THROWS_MESSAGE(
g_.SolveShortestPath(*source_, *target_, options_), ".*inf.*");
}

// Test the code path where the upper bounds are not all infinite or finite.
TEST_F(ThreeBoxes, InvalidLinearConstraintUpper2) {
const Matrix2d A = Matrix2d::Identity();
const Vector2d b{.5, .3};
const Vector2d c_good{1.0, kInf};
const Vector2d c_bad{1.0, -kInf};

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b, c_good), e_on_->xv()));
// b ≤ e_on_->xv() ≤ c_good. No error on the upper bound -- the infinity
// component is trivially feasible.
DRAKE_EXPECT_NO_THROW(g_.SolveShortestPath(*source_, *target_, options_));

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b, Vector2d::Constant(-kInf)),
e_on_->xv()));
// b ≤ e_on_->xv() ≤ -∞. We can't take the perspective of such a constraint,
// so solving should throw an error.
std::make_shared<LinearConstraint>(A, b, c_bad), e_on_->xv()));
// b ≤ e_on_->xv() ≤ c_bad. We can't take the perspective of the
// trivially-infeasible constraint, so solving should throw an error.
DRAKE_EXPECT_THROWS_MESSAGE(
g_.SolveShortestPath(*source_, *target_, options_), ".*inf.*");
}

// Test linear constraints with a lower bound of +inf.
TEST_F(ThreeBoxes, InvalidLinearConstraintLower) {
const Matrix2d A = Matrix2d::Identity();
const Vector2d b{.5, .3};
const Vector2d b_good{-1.0, -kInf};
const Vector2d b_bad{-1.0, kInf};
const Vector2d c{.5, .3};

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b_good, c), e_on_->xv()));
// b_good ≤ e_on_->xv() ≤ c. No error on the upper bound -- the infinity
// component is trivially feasible.
DRAKE_EXPECT_NO_THROW(g_.SolveShortestPath(*source_, *target_, options_));

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b_bad, c), e_on_->xv()));
// b_bad ≤ e_on_->xv() ≤ c. We can't take the perspective of the
// trivially-infeasible constraint, so solving should throw an error.
DRAKE_EXPECT_THROWS_MESSAGE(
g_.SolveShortestPath(*source_, *target_, options_), ".*inf.*");
}

// Test the code path where the lower bounds are not all infinite or finite.
TEST_F(ThreeBoxes, InvalidLinearConstraintLower2) {
const Matrix2d A = Matrix2d::Identity();
const Vector2d b_good{-1.0, -kInf};
const Vector2d b_bad{-1.0, kInf};
const Vector2d c{.5, .3};

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, b_good, c), e_on_->xv()));
// b_good ≤ e_on_->xv() ≤ c. No error on the upper bound -- the infinity
// component is trivially feasible.
DRAKE_EXPECT_NO_THROW(g_.SolveShortestPath(*source_, *target_, options_));

e_on_->AddConstraint(CreateBinding(
std::make_shared<LinearConstraint>(A, Vector2d::Constant(kInf), b),
e_on_->xv()));
// ∞ ≤ e_on_->xv() ≤ b. We can't take the perspective of such a constraint, so
// solving should throw an error.
std::make_shared<LinearConstraint>(A, b_bad, c), e_on_->xv()));
// b_bad ≤ e_on_->xv() ≤ c. We can't take the perspective of the
// trivially-infeasible constraint, so solving should throw an error.
DRAKE_EXPECT_THROWS_MESSAGE(
g_.SolveShortestPath(*source_, *target_, options_), ".*inf.*");
}
Expand Down
171 changes: 171 additions & 0 deletions planning/trajectory_optimization/gcs_trajectory_optimization.cc
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,7 @@ using solvers::LinearEqualityConstraint;
using solvers::QuadraticCost;
using symbolic::DecomposeLinearExpressions;
using symbolic::Expression;
using symbolic::Formula;
using symbolic::MakeMatrixContinuousVariable;
using symbolic::MakeVectorContinuousVariable;
using trajectories::BezierCurve;
Expand Down Expand Up @@ -316,6 +317,17 @@ Subgraph::Subgraph(
path_continuity_constraint,
{GetControlPoints(*u).col(order), GetControlPoints(*v).col(0)}));
}

// Construct placeholder variables.
placeholder_vertex_time_scaling_var_ = MakeVectorContinuousVariable(1, "t");
placeholder_vertex_control_points_var_ =
MakeVectorContinuousVariable(num_positions() * (order + 1), "x");
placeholder_edge_time_scaling_var_ =
std::make_pair(MakeVectorContinuousVariable(1, "tu"),
MakeVectorContinuousVariable(1, "tv"));
placeholder_edge_control_points_var_ = std::make_pair(
MakeVectorContinuousVariable(num_positions() * (order + 1), "xu"),
MakeVectorContinuousVariable(num_positions() * (order + 1), "xv"));
}

Subgraph::~Subgraph() = default;
Expand Down Expand Up @@ -638,6 +650,9 @@ void Subgraph::AddPathContinuityConstraints(int continuity_order) {
}

void Subgraph::AddContinuityConstraints(int continuity_order) {
// TODO(cohnt): Rewrite to use the generic AddCost and AddConstraint
// interfaces.

if (continuity_order == 0) {
throw std::runtime_error(
"Path continuity is enforced by default. Choose a higher order.");
Expand Down Expand Up @@ -739,6 +754,162 @@ symbolic::Variable Subgraph::GetTimeScaling(
return v.x()(v.x().size() - 1);
}

std::variant<Expression, Formula>
Subgraph::SubstituteVertexPlaceholderVariables(
const std::variant<Expression, Formula>& e, const Vertex* vertex) const {
int num_variables = num_positions() * (order_ + 1);
VectorXDecisionVariable control_points_vars(
GetControlPoints(*vertex).reshaped());

// Note: the logic is identical for symbolic::Expression and
// symbolic::Formula, but since there is no inheritance structure, we have to
// split into cases based on which type is actually used.
if (std::holds_alternative<Expression>(e)) {
Expression e_out = std::get<Expression>(e);
symbolic::Variables e_vars = e_out.GetVariables();

// Substitute the control point variables.
for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_vertex_control_points_var_[i])) {
e_out = e_out.Substitute(placeholder_vertex_control_points_var_[i],
control_points_vars[i]);
}
}
// Substitute the time scaling variable.
if (e_vars.include(placeholder_vertex_time_scaling_var_[0])) {
e_out = e_out.Substitute(placeholder_vertex_time_scaling_var_[0],
GetTimeScaling(*vertex));
}
return e_out;
} else {
Formula e_out = std::get<Formula>(e);
symbolic::Variables e_vars = e_out.GetFreeVariables();

for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_vertex_control_points_var_[i])) {
e_out = e_out.Substitute(placeholder_vertex_control_points_var_[i],
control_points_vars[i]);
}
}
if (e_vars.include(placeholder_vertex_time_scaling_var_[0])) {
e_out = e_out.Substitute(placeholder_vertex_time_scaling_var_[0],
GetTimeScaling(*vertex));
}
return e_out;
}
}

std::variant<Expression, Formula> Subgraph::SubstituteEdgePlaceholderVariables(
const std::variant<Expression, Formula>& e, const Edge* edge) const {
const Vertex& v1 = edge->u();
const Vertex& v2 = edge->v();
int num_variables = num_positions() * (order_ + 1);

VectorXDecisionVariable control_points_vars_1(
GetControlPoints(v1).reshaped());
VectorXDecisionVariable control_points_vars_2(
GetControlPoints(v2).reshaped());

// Note: the logic is identical for symbolic::Expression and
// symbolic::Formula, but since there is no inheritance structure, we have to
// split into cases based on which type is actually used.
if (std::holds_alternative<Expression>(e)) {
Expression e_out = std::get<Expression>(e);
symbolic::Variables e_vars = e_out.GetVariables();

// Substitute the control point variables for the first vertex.
for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_edge_control_points_var_.first[i])) {
e_out = e_out.Substitute(placeholder_edge_control_points_var_.first[i],
control_points_vars_1[i]);
}
}
// Substitute the control point variables for the second vertex.
for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_edge_control_points_var_.second[i])) {
e_out = e_out.Substitute(placeholder_edge_control_points_var_.second[i],
control_points_vars_2[i]);
}
}
// Substitute the time scaling variable for the first vertex.
if (e_vars.include(placeholder_edge_time_scaling_var_.first[0])) {
e_out = e_out.Substitute(placeholder_edge_time_scaling_var_.first[0],
GetTimeScaling(v1));
}
// Substitute the time scaling variable for the second vertex.
if (e_vars.include(placeholder_edge_time_scaling_var_.second[0])) {
e_out = e_out.Substitute(placeholder_edge_time_scaling_var_.second[0],
GetTimeScaling(v2));
}
return e_out;
} else {
Formula e_out = std::get<Formula>(e);
symbolic::Variables e_vars = e_out.GetFreeVariables();

for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_edge_control_points_var_.first[i])) {
e_out = e_out.Substitute(placeholder_edge_control_points_var_.first[i],
control_points_vars_1[i]);
}
}
for (int i = 0; i < num_variables; ++i) {
if (e_vars.include(placeholder_edge_control_points_var_.second[i])) {
e_out = e_out.Substitute(placeholder_edge_control_points_var_.second[i],
control_points_vars_2[i]);
}
}
if (e_vars.include(placeholder_edge_time_scaling_var_.first[0])) {
e_out = e_out.Substitute(placeholder_edge_time_scaling_var_.first[0],
GetTimeScaling(v1));
}
if (e_vars.include(placeholder_edge_time_scaling_var_.second[0])) {
e_out = e_out.Substitute(placeholder_edge_time_scaling_var_.second[0],
GetTimeScaling(v2));
}
return e_out;
}
}

void Subgraph::AddVertexCost(
const Expression& e,
const std::unordered_set<Transcription>& used_in_transcription) {
for (Vertex*& vertex : vertices_) {
Expression post_substitution =
std::get<Expression>(SubstituteVertexPlaceholderVariables(e, vertex));
vertex->AddCost(post_substitution, used_in_transcription);
}
}

void Subgraph::AddVertexConstraint(
const Formula& e,
const std::unordered_set<Transcription>& used_in_transcription) {
for (Vertex*& vertex : vertices_) {
Formula post_substitution =
std::get<Formula>(SubstituteVertexPlaceholderVariables(e, vertex));
vertex->AddConstraint(post_substitution, used_in_transcription);
}
}

void Subgraph::AddEdgeCost(
const Expression& e,
const std::unordered_set<Transcription>& used_in_transcription) {
for (Edge*& edge : edges_) {
Expression post_substitution =
std::get<Expression>(SubstituteEdgePlaceholderVariables(e, edge));
edge->AddCost(post_substitution, used_in_transcription);
}
}

void Subgraph::AddEdgeConstraint(
const symbolic::Formula& e,
const std::unordered_set<Transcription>& used_in_transcription) {
for (Edge*& edge : edges_) {
Formula post_substitution =
std::get<Formula>(SubstituteEdgePlaceholderVariables(e, edge));
edge->AddConstraint(post_substitution, used_in_transcription);
}
}

EdgesBetweenSubgraphs::EdgesBetweenSubgraphs(
const Subgraph& from_subgraph, const Subgraph& to_subgraph,
const ConvexSet* subspace, GcsTrajectoryOptimization* traj_opt,
Expand Down
Loading