Drake
Drake C++ Documentation
SemidefiniteRelaxationOptions Struct Reference

Detailed Description

Configuration options for the MakeSemidefiniteRelaxation.

Throughout these options, we refer to the variables of the original optimization program as y, and the semidefinite variable of the associate relaxation as X.

X has the structure X = [Y, y] [yᵀ, one]

#include <drake/solvers/semidefinite_relaxation.h>

Public Member Functions

void set_to_strongest ()
 Configure the semidefinite relaxation options to provide the strongest possible semidefinite relaxation that we currently support. More...
 
void set_to_weakest ()
 Configure the semidefinite relaxation options to provide the weakest semidefinite relaxation that we currently support. More...
 

Public Attributes

bool add_implied_linear_equality_constraints {true}
 Given a program with the linear constraints Ay ≤ b, sets whether to add the implied linear constraints [A,-b]X[A,-b]ᵀ ≤ 0 to the semidefinite relaxation. More...
 
bool add_implied_linear_constraints {true}
 Given a program with the linear equality constraints Ay = b, sets whether to add the implied linear constraints [A, -b]X = 0 to the semidefinite relaxation. More...
 
bool preserve_convex_quadratic_constraints {false}
 2025-04-01 DEPRECATION NOTICE: The convex quadratic constraints are already implied by a linear constraint that is always added to the semidefinite relaxation. More...
 

Member Function Documentation

◆ set_to_strongest()

void set_to_strongest ( )

Configure the semidefinite relaxation options to provide the strongest possible semidefinite relaxation that we currently support.

This in general will give the tightest convex relaxation we support, but the longest solve times.

◆ set_to_weakest()

void set_to_weakest ( )

Configure the semidefinite relaxation options to provide the weakest semidefinite relaxation that we currently support.

This in general will create the loosest convex relaxation we support, but the shortest solve times. This is equivalent to the standard Shor Relaxation (see Quadratic Optimization Problems by NZ Shor or Semidefinite Programming by Vandenberghe and Boyd).

Member Data Documentation

◆ add_implied_linear_constraints

bool add_implied_linear_constraints {true}

Given a program with the linear equality constraints Ay = b, sets whether to add the implied linear constraints [A, -b]X = 0 to the semidefinite relaxation.

◆ add_implied_linear_equality_constraints

bool add_implied_linear_equality_constraints {true}

Given a program with the linear constraints Ay ≤ b, sets whether to add the implied linear constraints [A,-b]X[A,-b]ᵀ ≤ 0 to the semidefinite relaxation.

◆ preserve_convex_quadratic_constraints

bool preserve_convex_quadratic_constraints {false}

2025-04-01 DEPRECATION NOTICE: The convex quadratic constraints are already implied by a linear constraint that is always added to the semidefinite relaxation.

Therefore, this flag has no effect on the solution to the overall program and will be deprecated on April 1st, 2025.

Given a convex quadratic constraint xᵀP x + xᵀq + r <= 0 it is always stronger to add the linearized constraint Tr(PX) + xᵀq + r <= 0 (as is already done for all convex and nonconvex quadratic constraints), rendering the original convex quadratic constraints unnecessary.


The documentation for this struct was generated from the following file: