Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
iris.h File Reference
#include <map>
#include <memory>
#include <optional>
#include <string>
#include <vector>
#include "drake/common/drake_deprecated.h"
#include "drake/common/name_value.h"
#include "drake/geometry/meshcat.h"
#include "drake/geometry/optimization/convex_set.h"
#include "drake/geometry/optimization/hpolyhedron.h"
#include "drake/multibody/plant/multibody_plant.h"
Include dependency graph for iris.h:
This graph shows which files directly or indirectly include this file:

Classes

struct  IrisOptions
 Configuration options for the IRIS algorithm. More...

Namespaces

namespace  drake
namespace  drake::geometry
namespace  drake::geometry::optimization

Typedefs

typedef std::map< std::string, HPolyhedronIrisRegions
 Defines a standardized representation for (named) IrisRegions, which can be serialized in both C++ and Python.

Functions

HPolyhedron Iris (const ConvexSets &obstacles, const Eigen::Ref< const Eigen::VectorXd > &sample, const HPolyhedron &domain, const IrisOptions &options=IrisOptions())
 The IRIS (Iterative Region Inflation by Semidefinite programming) algorithm, as described in.
ConvexSets MakeIrisObstacles (const QueryObject< double > &query_object, std::optional< FrameId > reference_frame=std::nullopt)
 Constructs ConvexSet representations of obstacles for IRIS in 3D using the geometry from a SceneGraph QueryObject.
HPolyhedron IrisNp (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &context, const IrisOptions &options=IrisOptions())
 A variation of the Iris (Iterative Region Inflation by Semidefinite programming) algorithm which finds collision-free regions in the configuration space of plant.
HPolyhedron IrisInConfigurationSpace (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &context, const IrisOptions &options=IrisOptions())
 (Deprecated.)
void SetEdgeContainmentTerminationCondition (IrisOptions *iris_options, const Eigen::Ref< const Eigen::VectorXd > &x_1, const Eigen::Ref< const Eigen::VectorXd > &x_2, const double epsilon=1e-3, const double tol=1e-6)
 Modifies the iris_options to facilitate finding a region that contains the edge between x_1 and x_2.