Drake
Drake C++ Documentation
IrisZoOptions Struct Reference

Detailed Description

IrisZoOptions collects all parameters for the IRIS-ZO algorithm.

Warning
This feature is considered to be experimental and may change or be removed at any time, without any deprecation notice ahead of time.
See also
IrisZo for more details.

#include <drake/planning/iris/iris_zo.h>

Public Member Functions

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

Public Attributes

int num_particles = 1e3
 Number of particles used to estimate the closest collision. More...
 
double tau = 0.5
 Decision threshold for the unadaptive test. More...
 
double delta = 5e-2
 Upper bound on the probability the returned region has a fraction-in-collision greater than epsilon. More...
 
double epsilon = 1e-2
 Admissible fraction of the region volume allowed to be in collision. More...
 
std::optional< Eigen::MatrixXd > containment_points {std::nullopt}
 Points that are guaranteed to be contained in the final region provided their convex hull is collision free. More...
 
int max_iterations {3}
 Maximum number of alternations between the ellipsoid and the separating planes step (a.k.a. More...
 
int max_iterations_separating_planes {20}
 Maximum number of rounds of adding faces to the polytope per outer iteration. More...
 
int max_separating_planes_per_iteration {-1}
 Maximum number of faces to add per inner iteration. More...
 
int bisection_steps {10}
 Maximum number of bisection steps. More...
 
Parallelism parallelism {Parallelism::Max()}
 Number of threads to use when updating the particles. More...
 
bool verbose {false}
 Enables print statements indicating the progress of IrisZo. More...
 
bool require_sample_point_is_contained {true}
 The initial polytope is guaranteed to contain the point if that point is collision-free. More...
 
double configuration_space_margin {1e-2}
 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...
 
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...
 
int random_seed {1234}
 This option sets the random seed for random sampling throughout the algorithm. More...
 
int mixing_steps {50}
 Number of mixing steps used for hit-and-run sampling. More...
 
std::shared_ptr< geometry::Meshcatmeshcat {}
 Passing a meshcat instance may enable debugging visualizations; this currently and when the configuration space is <= 3 dimensional. More...
 

Constructor & Destructor Documentation

◆ IrisZoOptions()

IrisZoOptions ( )
default

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

◆ bisection_steps

int bisection_steps {10}

Maximum number of bisection steps.

◆ configuration_space_margin

double configuration_space_margin {1e-2}

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.

◆ containment_points

std::optional<Eigen::MatrixXd> containment_points {std::nullopt}

Points that are guaranteed to be contained in the final region provided their convex hull is collision free.

Note that if the containment points are closer than configuration_margin to an obstacle we will relax the margin in favor of including the containment points. The matrix containment_points is expected to be of the shape dimension times number of points. IrisZo throws if the center of the starting ellipsoid is not contained in the convex hull of these containment points.

◆ delta

double delta = 5e-2

Upper bound on the probability the returned region has a fraction-in-collision greater than epsilon.

◆ epsilon

double epsilon = 1e-2

Admissible fraction of the region volume allowed to be in collision.

◆ max_iterations

int max_iterations {3}

Maximum number of alternations between the ellipsoid and the separating planes step (a.k.a.

outer iterations).

◆ max_iterations_separating_planes

int max_iterations_separating_planes {20}

Maximum number of rounds of adding faces to the polytope per outer iteration.

◆ max_separating_planes_per_iteration

int max_separating_planes_per_iteration {-1}

Maximum number of faces to add per inner iteration.

Setting the value to -1 means there is no limit to the number of faces that can be added.

◆ meshcat

std::shared_ptr<geometry::Meshcat> meshcat {}

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

◆ mixing_steps

int mixing_steps {50}

Number of mixing steps used for hit-and-run sampling.

◆ num_particles

int num_particles = 1e3

Number of particles used to estimate the closest collision.

◆ parallelism

Parallelism parallelism {Parallelism::Max()}

Number of threads to use when updating the particles.

If the user requests more threads than the CollisionChecker supports, that number of threads will be used instead.

◆ random_seed

int random_seed {1234}

This option sets the random seed for random sampling throughout the algorithm.

◆ 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 {true}

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

◆ tau

double tau = 0.5

Decision threshold for the unadaptive test.

Choosing a small value increases both the cost and the power statistical test. Increasing the value of tau makes running an individual test cheaper but decreases its power to accept a polytope. We find choosing a value of 0.5 a good trade-off.

◆ 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.

◆ verbose

bool verbose {false}

Enables print statements indicating the progress of IrisZo.


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