Various options which are common to the sampling-based algorithms IrisNp2 and IrisZo for generating collision free polytopes in configuration space.
#include <drake/planning/iris/iris_common.h>
Public Member Functions | |
template<typename Archive > | |
void | Serialize (Archive *a) |
Passes this object to an Archive. More... | |
CommonSampledIrisOptions ()=default | |
Implements CopyConstructible, CopyAssignable, MoveConstructible, MoveAssignable | |
CommonSampledIrisOptions (const CommonSampledIrisOptions &)=default | |
CommonSampledIrisOptions & | operator= (const CommonSampledIrisOptions &)=default |
CommonSampledIrisOptions (CommonSampledIrisOptions &&)=default | |
CommonSampledIrisOptions & | operator= (CommonSampledIrisOptions &&)=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 {10} |
Maximum number of faces to add per inner iteration. 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... | |
bool | remove_all_collisions_possible {true} |
A region may satisfy the user-requested fraction in-collision, but still have some of the samples drawn be in-collision. 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... | |
bool | sample_particles_in_parallel {false} |
If true, the hit-and-run procedure is run in parallel to quickly draw all the samples necessary. More... | |
std::shared_ptr< geometry::Meshcat > | meshcat {} |
Passing a meshcat instance may enable debugging visualizations when the configuration space is <= 3 dimensional. More... | |
const solvers::MathematicalProgram * | prog_with_additional_constraints {} |
By default, IRIS-ZO only considers collision avoidance constraints. More... | |
|
default |
|
default |
|
default |
|
default |
|
default |
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.
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.
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.
double delta = 5e-2 |
Upper bound on the probability the returned region has a fraction-in-collision greater than epsilon
.
double epsilon = 1e-2 |
Admissible fraction of the region volume allowed to be in collision.
int max_iterations {3} |
Maximum number of alternations between the ellipsoid and the separating planes step (a.k.a.
outer iterations).
int max_iterations_separating_planes {20} |
Maximum number of rounds of adding faces to the polytope per outer iteration.
int max_separating_planes_per_iteration {10} |
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.
std::shared_ptr<geometry::Meshcat> meshcat {} |
Passing a meshcat instance may enable debugging visualizations when the configuration space is <= 3 dimensional.
int mixing_steps {50} |
Number of mixing steps used for hit-and-run sampling.
int num_particles = 1e3 |
Number of particles used to estimate the closest collision.
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. However, see also parameterization_is_threadsafe
.
const solvers::MathematicalProgram* prog_with_additional_constraints {} |
By default, IRIS-ZO only considers collision avoidance constraints.
This option can be used to pass additional constraints that should be satisfied by the output 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-ZO will silently ignore any costs in prog_with_additional_constraints
. If any constraints are not threadsafe, then parallelism
will be overridden, and only one thread will be used.
int random_seed {1234} |
This option sets the random seed for random sampling throughout the algorithm.
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.
bool remove_all_collisions_possible {true} |
A region may satisfy the user-requested fraction in-collision, but still have some of the samples drawn be in-collision.
If this flag is true, those samples will also be used to produce hyperplanes. This produces slightly smaller regions with more faces, but the region will beat the user-requested fraction in-collision by a larger margin.
bool require_sample_point_is_contained {true} |
The initial polytope is guaranteed to contain the point if that point is collision-free.
bool sample_particles_in_parallel {false} |
If true, the hit-and-run procedure is run in parallel to quickly draw all the samples necessary.
When the statistical test requires many samples (e.g. due to constructing regions with a very low fraction in collision with very high probability), the process of drawing the samples may become a major time cost. Drawing the samples in parallel can lead to a major speedup, at the cost of a sampling from a distribution that's slightly further from a uniform distribution (due to the lower cumulative mixing time).
double tau = 0.5 |
Decision threshold for the unadaptive test.
Choosing a small value increases both the cost and the power of the 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.
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.
bool verbose {false} |
Enables print statements indicating the progress of IrisZo.