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
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
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.
#include <drake/solvers/mixed_integer_rotation_constraint.h>
Classes | |
| struct | ReturnType |
Public Types | |
| enum class | Approach { kBoxSphereIntersection , kBilinearMcCormick , kBoth } |
Public Member Functions | |
| MixedIntegerRotationConstraintGenerator (Approach approach, int num_intervals_per_half_axis, IntervalBinning interval_binning) | |
| Constructor. | |
| 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. | |
| const Eigen::VectorXd & | phi () const |
| Getter for φ. | |
| const Eigen::VectorXd | phi_nonnegative () const |
| Getter for φ₊, the non-negative part of φ. | |
| Approach | approach () const |
| int | num_intervals_per_half_axis () const |
| IntervalBinning | interval_binning () const |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
| MixedIntegerRotationConstraintGenerator (const MixedIntegerRotationConstraintGenerator &)=default | |
| MixedIntegerRotationConstraintGenerator & | operator= (const MixedIntegerRotationConstraintGenerator &)=default |
| MixedIntegerRotationConstraintGenerator (MixedIntegerRotationConstraintGenerator &&)=default | |
| MixedIntegerRotationConstraintGenerator & | operator= (MixedIntegerRotationConstraintGenerator &&)=default |
|
strong |
|
default |
|
default |
| MixedIntegerRotationConstraintGenerator | ( | Approach | approach, |
| int | num_intervals_per_half_axis, | ||
| IntervalBinning | interval_binning ) |
Constructor.
| approach | Refer to MixedIntegerRotationConstraintGenerator::Approach for the details. |
| num_intervals_per_half_axis | We 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_binning | The 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. |
| 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.
| R | The rotation matrix on which the SO(3) constraint is imposed. |
| prog | The optimization program to which the mixed-integer constraints (and additional variables) are added. |
| Approach approach | ( | ) | const |
| IntervalBinning interval_binning | ( | ) | const |
| int num_intervals_per_half_axis | ( | ) | const |
|
default |
|
default |
| const Eigen::VectorXd & phi | ( | ) | const |
Getter for φ.
| const Eigen::VectorXd phi_nonnegative | ( | ) | const |
Getter for φ₊, the non-negative part of φ.