Drake
Drake C++ Documentation
MixedIntegerRotationConstraintGenerator Class Reference

Detailed Description

We relax the non-convex SO(3) constraint on rotation matrix R to mixed-integer linear constraints.

The formulation of these constraints are described in Global Inverse Kinematics via Mixed-integer Convex Optimization by Hongkai Dai, Gregory Izatt and Russ Tedrake, ISRR, 2017

The SO(3) constraint on a rotation matrix R = [r₁, r₂, r₃], rᵢ∈ℝ³ is

rᵢᵀrᵢ = 1 (1)
rᵢᵀrⱼ = 0 (2)
r₁ x r₂ = r₃ (3)

To relax SO(3) constraint on rotation matrix R, we divide the range [-1, 1] (the range of each entry in R) into smaller intervals [φ(i), φ(i+1)], and then relax the SO(3) constraint within each interval. We provide 3 approaches for relaxation

  1. By replacing each bilinear product in constraint (1), (2) and (3) with a new variable, in the McCormick envelope of the bilinear product w = x * y.
  2. By considering the intersection region between axis-aligned boxes, and the surface of a unit sphere in 3D.
  3. By combining the two approaches above. This will result in a tighter relaxation.

These three approaches give different relaxation of SO(3) constraint (the feasible sets for each relaxation are different), and different computation speed. The users can switch between the approaches to find the best fit for their problem.

Note
If you have several rotation matrices that all need to be relaxed through mixed-integer constraint, then you can create a single MixedIntegerRotationConstraintGenerator object, and add the mixed-integer constraint to each rotation matrix, by calling AddToProgram() function repeatedly.

#include <drake/solvers/mixed_integer_rotation_constraint.h>

Classes

struct  ReturnType
 

Public Types

enum  Approach { kBoxSphereIntersection, kBilinearMcCormick, kBoth }
 

Public Member Functions

 MixedIntegerRotationConstraintGenerator (Approach approach, int num_intervals_per_half_axis, IntervalBinning interval_binning)
 Constructor. More...
 
ReturnType AddToProgram (const Eigen::Ref< const MatrixDecisionVariable< 3, 3 >> &R, MathematicalProgram *prog) const
 Add the mixed-integer linear constraints to the optimization program, as a relaxation of SO(3) constraint on the rotation matrix R. More...
 
const Eigen::VectorXd & phi () const
 Getter for φ. More...
 
const Eigen::VectorXd phi_nonnegative () const
 Getter for φ₊, the non-negative part of φ. More...
 
Approach approach () const
 
int num_intervals_per_half_axis () const
 
IntervalBinning interval_binning () const
 
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable
 MixedIntegerRotationConstraintGenerator (const MixedIntegerRotationConstraintGenerator &)=default
 
MixedIntegerRotationConstraintGeneratoroperator= (const MixedIntegerRotationConstraintGenerator &)=default
 
 MixedIntegerRotationConstraintGenerator (MixedIntegerRotationConstraintGenerator &&)=default
 
MixedIntegerRotationConstraintGeneratoroperator= (MixedIntegerRotationConstraintGenerator &&)=default
 

Member Enumeration Documentation

◆ Approach

enum Approach
strong
Enumerator
kBoxSphereIntersection 

Relax SO(3) constraint by considering the intersection between boxes and the unit sphere surface.

kBilinearMcCormick 

Relax SO(3) constraint by considering the McCormick envelope on the bilinear product.

kBoth 

Relax SO(3) constraint by considering both the intersection between boxes and the unit sphere surface, and the McCormick envelope on the bilinear product.

Constructor & Destructor Documentation

◆ MixedIntegerRotationConstraintGenerator() [1/3]

◆ MixedIntegerRotationConstraintGenerator() [2/3]

◆ MixedIntegerRotationConstraintGenerator() [3/3]

MixedIntegerRotationConstraintGenerator ( Approach  approach,
int  num_intervals_per_half_axis,
IntervalBinning  interval_binning 
)

Constructor.

Parameters
approachRefer to MixedIntegerRotationConstraintGenerator::Approach for the details.
num_intervals_per_half_axisWe will cut the range [-1, 1] evenly to 2 * num_intervals_per_half_axis small intervals. The number of binary variables will depend on the number of intervals.
interval_binningThe binning scheme we use to add SOS2 constraint with binary variables. If interval_binning = kLinear, then we will add 9 * 2 * num_intervals_per_half_axis binary variables; if interval_binning = kLogarithmic, then we will add 9 * (1 + log₂(num_intervals_per_half_axis)) binary variables. Refer to AddLogarithmicSos2Constraint and AddSos2Constraint for more details.

Member Function Documentation

◆ AddToProgram()

ReturnType AddToProgram ( const Eigen::Ref< const MatrixDecisionVariable< 3, 3 >> &  R,
MathematicalProgram prog 
) const

Add the mixed-integer linear constraints to the optimization program, as a relaxation of SO(3) constraint on the rotation matrix R.

Parameters
RThe rotation matrix on which the SO(3) constraint is imposed.
progThe optimization program to which the mixed-integer constraints (and additional variables) are added.

◆ approach()

Approach approach ( ) const

◆ interval_binning()

IntervalBinning interval_binning ( ) const

◆ num_intervals_per_half_axis()

int num_intervals_per_half_axis ( ) const

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ phi()

const Eigen::VectorXd& phi ( ) const

Getter for φ.

◆ phi_nonnegative()

const Eigen::VectorXd phi_nonnegative ( ) const

Getter for φ₊, the non-negative part of φ.


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