Drake
Drake C++ Documentation

Detailed Description

Configuration options for the IRIS algorithm.

#include <drake/geometry/optimization/iris.h>

Public Member Functions

template<typename Archive >
void Serialize (Archive *a)
 Passes this object to an Archive. More...
 

Public Attributes

bool require_sample_point_is_contained {false}
 The initial polytope is guaranteed to contain the point if that point is collision-free. More...
 
int iteration_limit {100}
 Maximum number of iterations. More...
 
double termination_threshold {2e-2}
 IRIS will terminate if the change in the volume of the hyperellipsoid between iterations is less that this threshold. More...
 
double relative_termination_threshold {1e-3}
 IRIS will terminate if the change in the volume of the hyperellipsoid between iterations is less that this percent of the previous best volume. More...
 
double configuration_space_margin {1e-2}
 For IRIS in configuration space, we retreat by this margin from each C-space obstacle in order to avoid the possibility of requiring an infinite number of faces to approximate a curved boundary. More...
 
int num_collision_infeasible_samples {5}
 For each possible collision, IRIS will search for a counter-example by formulating a (likely nonconvex) optimization problem. More...
 
ConvexSets configuration_obstacles {}
 For IRIS in configuration space, it can be beneficial to not only specify task-space obstacles (passed in through the plant) but also obstacles that are defined by convex sets in the configuration space. More...
 
std::optional< Hyperellipsoidstarting_ellipse {}
 The initial hyperellipsoid that IRIS will use for calculating hyperplanes in the first iteration. More...
 
std::optional< HPolyhedronbounding_region {}
 Optionally allows the caller to restrict the space within which IRIS regions are allowed to grow. More...
 
bool verify_domain_boundedness {true}
 If the user knows the intersection of bounding_region and the domain (for IRIS) or plant joint limits (for IrisInConfigurationSpace) is bounded, setting this flag to false will skip the boundedness check that IRIS and IrisInConfigurationSpace perform (leading to a small speedup, as checking boundedness requires solving optimization problems). More...
 
const solvers::MathematicalProgramprog_with_additional_constraints {}
 By default, IRIS in configuration space certifies regions for collision avoidance constraints and joint limits. More...
 
int num_additional_constraint_infeasible_samples {5}
 For each constraint in prog_with_additional_constraints, IRIS will search for a counter-example by formulating a (likely nonconvex) optimization problem. More...
 
int random_seed {1234}
 The only randomization in IRIS is the random sampling done to find counter-examples for the additional constraints using in IrisInConfigurationSpace. More...
 
std::shared_ptr< Meshcatmeshcat {}
 Passing a meshcat instance may enable debugging visualizations; this currently only happens in IrisInConfigurationSpace and when the configuration space is <= 3 dimensional. More...
 
std::function< bool(const HPolyhedron &)> termination_func {}
 A user-defined termination function to determine whether the iterations should stop. More...
 
int mixing_steps {10}
 The mixing_steps parameters is passed to HPolyhedron::UniformSample to control the total number of hit-and-run steps taken for each new random sample. More...
 
std::optional< solvers::SolverOptionssolver_options
 The SolverOptions used in the optimization program. More...
 
double convexity_radius_stepback {1e-3}
 Artificial joint limits are added to continuous revolute joints and planar joints with an unbounded revolute degree-of-freedom on a per-region basis. More...
 

Member Function Documentation

◆ Serialize()

void Serialize ( Archive *  a)

Passes this object to an Archive.

Refer to YAML Serialization for background. Note: This only serializes options that are YAML built-in types.

Member Data Documentation

◆ bounding_region

std::optional<HPolyhedron> bounding_region {}

Optionally allows the caller to restrict the space within which IRIS regions are allowed to grow.

By default, IRIS regions are bounded by the domain argument in the case of Iris or the joint limits of the input plant in the case of IrisInConfigurationSpace. If this option is specified, IRIS regions will be confined to the intersection between the domain and bounding_region

◆ configuration_obstacles

ConvexSets configuration_obstacles {}

For IRIS in configuration space, it can be beneficial to not only specify task-space obstacles (passed in through the plant) but also obstacles that are defined by convex sets in the configuration space.

This option can be used to pass in such configuration space obstacles.

◆ configuration_space_margin

double configuration_space_margin {1e-2}

For IRIS in configuration space, we retreat by this margin from each C-space obstacle in order to avoid the possibility of requiring an infinite number of faces to approximate a curved boundary.

◆ convexity_radius_stepback

double convexity_radius_stepback {1e-3}

Artificial joint limits are added to continuous revolute joints and planar joints with an unbounded revolute degree-of-freedom on a per-region basis.

If the seed point value for that joint is θ, then the limits are θ - π/2 + convexity_radius_stepback and θ + π/2 - convexity_radius_stepback. Setting this to a negative number allows growing larger regions, but those regions must then be partitioned to be used with GcsTrajectoryOptimization. See Geodesic Convexity for more details. IrisInConfigurationSpace throws if this value is not smaller than π/2.

◆ iteration_limit

int iteration_limit {100}

Maximum number of iterations.

◆ meshcat

std::shared_ptr<Meshcat> meshcat {}

Passing a meshcat instance may enable debugging visualizations; this currently only happens in IrisInConfigurationSpace and when the configuration space is <= 3 dimensional.

◆ mixing_steps

int mixing_steps {10}

The mixing_steps parameters is passed to HPolyhedron::UniformSample to control the total number of hit-and-run steps taken for each new random sample.

◆ num_additional_constraint_infeasible_samples

int num_additional_constraint_infeasible_samples {5}

For each constraint in prog_with_additional_constraints, IRIS will search for a counter-example by formulating a (likely nonconvex) optimization problem.

The initial guess for this optimization is taken by sampling uniformly inside the current IRIS region. This option controls the termination condition for that counter-example search, defining the number of consecutive failures to find a counter-example requested before moving on to the next constraint.

◆ num_collision_infeasible_samples

int num_collision_infeasible_samples {5}

For each possible collision, IRIS will search for a counter-example by formulating a (likely nonconvex) optimization problem.

The initial guess for this optimization is taken by sampling uniformly inside the current IRIS region. This option controls the termination condition for that counter-example search, defining the number of consecutive failures to find a counter-example requested before moving on to the next constraint.

◆ prog_with_additional_constraints

const solvers::MathematicalProgram* prog_with_additional_constraints {}

By default, IRIS in configuration space certifies regions for collision avoidance constraints and joint limits.

This option can be used to pass additional constraints that should be satisfied by the IRIS region. We accept these in the form of a MathematicalProgram:

find q subject to g(q) ≤ 0.

The decision_variables() for the program are taken to define q. IRIS will silently ignore any costs in prog_with_additional_constraints, and will throw std::runtime_error if it contains any unsupported constraints.

For example, one could create an InverseKinematics problem with rich kinematic constraints, and then pass InverseKinematics::prog() into this option.

◆ random_seed

int random_seed {1234}

The only randomization in IRIS is the random sampling done to find counter-examples for the additional constraints using in IrisInConfigurationSpace.

Use this option to set the initial seed.

◆ relative_termination_threshold

double relative_termination_threshold {1e-3}

IRIS will terminate if the change in the volume of the hyperellipsoid between iterations is less that this percent of the previous best volume.

This termination condition can be disabled by setting to a negative value.

◆ require_sample_point_is_contained

bool require_sample_point_is_contained {false}

The initial polytope is guaranteed to contain the point if that point is collision-free.

However, the IRIS alternation objectives do not include (and can not easily include) a constraint that the original sample point is contained. Therefore, the IRIS paper recommends that if containment is a requirement, then the algorithm should simply terminate early if alternations would ever cause the set to not contain the point.

◆ solver_options

std::optional<solvers::SolverOptions> solver_options

The SolverOptions used in the optimization program.

◆ starting_ellipse

std::optional<Hyperellipsoid> starting_ellipse {}

The initial hyperellipsoid that IRIS will use for calculating hyperplanes in the first iteration.

If no hyperellipsoid is provided, a small hypershpere centered at the given sample will be used.

◆ termination_func

std::function<bool(const HPolyhedron&)> termination_func {}

A user-defined termination function to determine whether the iterations should stop.

This function is called after computing each hyperplane at every IRIS iteration. If the function returns true, then the computations will stop and the last step region will be returned. Therefore, it is highly recommended that the termination function possesses a monotonic property such that for any two HPolyhedrons A and B such that B ⊆ A, we have if termination(A) -> termination(B). For example, a valid termination function is to check whether if the region does not contain any of a set of desired points.

auto termination_func = [](const HPolyhedron& set) {
for (const VectorXd& point : desired_points) {
if (!set.PointInSet(point)) {
return true;
}
}
return false;
};

The algorithm will stop when as soon as the region leaves one of the desired points, in a similar way to how require_sample_point_is_contained is enforced.

◆ termination_threshold

double termination_threshold {2e-2}

IRIS will terminate if the change in the volume of the hyperellipsoid between iterations is less that this threshold.

This termination condition can be disabled by setting to a negative value.

◆ verify_domain_boundedness

bool verify_domain_boundedness {true}

If the user knows the intersection of bounding_region and the domain (for IRIS) or plant joint limits (for IrisInConfigurationSpace) is bounded, setting this flag to false will skip the boundedness check that IRIS and IrisInConfigurationSpace perform (leading to a small speedup, as checking boundedness requires solving optimization problems).

If the intersection turns out to be unbounded, this will lead to undefined behavior.


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