Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
GlobalInverseKinematics::Options Struct Reference

#include <drake/multibody/inverse_kinematics/global_inverse_kinematics.h>

Public Member Functions

 Options ()

Public Attributes

int num_intervals_per_half_axis {2}
solvers::MixedIntegerRotationConstraintGenerator::Approach approach
solvers::IntervalBinning interval_binning
bool linear_constraint_only {false}
 If true, add only mixed-integer linear constraints in the constructor of GlobalInverseKinematics.

Constructor & Destructor Documentation

◆ Options()

Options ( )

Member Data Documentation

◆ approach

Initial value:
{
solvers::MixedIntegerRotationConstraintGenerator::Approach::
kBilinearMcCormick}

◆ interval_binning

solvers::IntervalBinning interval_binning
Initial value:
{
@ kLogarithmic
Definition mixed_integer_optimization_util.h:177

◆ linear_constraint_only

bool linear_constraint_only {false}

If true, add only mixed-integer linear constraints in the constructor of GlobalInverseKinematics.

The mixed-integer relaxation is tighter with nonlinear constraints (such as Lorentz cone constraint) than with linear constraints, but the optimization takes more time with nonlinear constraints.

◆ num_intervals_per_half_axis

int num_intervals_per_half_axis {2}

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