|
| class | AffineBall |
| | Implements an ellipsoidal convex set represented as an affine scaling of the unit ball {Bu + center | |u|₂ ≤ 1}. More...
|
| class | AffineSubspace |
| | An affine subspace (also known as a "flat", a "linear variety", or a "linear
manifold") is a vector subspace of some Euclidean space, potentially translated so as to not pass through the origin. More...
|
| class | CartesianProduct |
| | The Cartesian product of convex sets is a convex set: S = X₁ × X₂ × ⋯ × Xₙ = {(x₁, x₂, ..., xₙ) | x₁ ∈ X₁, x₂ ∈ X₂, ..., xₙ ∈ Xₙ}. More...
|
| class | CIrisCollisionGeometry |
| | This class contains the necessary information about the collision geometry used in C-IRIS. More...
|
| class | ConvexHull |
| | Implements the convex hull of a set of convex sets. More...
|
| class | ConvexSet |
| | Abstract base class for defining a convex set. More...
|
| class | CspaceFreeBox |
| | This class tries to find large axis-aligned bounding boxes in the configuration space, such that all configurations in the boxes are collision free. More...
|
| class | CspaceFreePolytope |
| | This class tries to find large convex polytopes in the tangential-configuration space, such that all configurations in the convex polytopes is collision free. More...
|
| class | CspaceFreePolytopeBase |
| | This virtual class is the base of CspaceFreePolytope and CspaceFreeBox. More...
|
| struct | CSpaceSeparatingPlane |
| | Wraps the information that a pair of collision geometries are separated by a plane. More...
|
| struct | FindSeparationCertificateOptions |
| struct | GcsGraphvizOptions |
| class | GraphOfConvexSets |
| | GraphOfConvexSets (GCS) implements the design pattern and optimization problems first introduced in the paper "Shortest Paths in Graphs of Convex Sets". More...
|
| struct | GraphOfConvexSetsOptions |
| class | HPolyhedron |
| | Implements a polyhedral convex set using the half-space representation: {x| A x ≤ b}. More...
|
| class | Hyperellipsoid |
| | Implements an ellipsoidal convex set represented by the quadratic form {x
| (x-center)ᵀAᵀA(x-center) ≤ 1}. More...
|
| class | Hyperrectangle |
| | Axis-aligned hyperrectangle in Rᵈ defined by its lower bounds and upper bounds as {x| lb ≤ x ≤ ub}. More...
|
| class | ImplicitGraphOfConvexSets |
| | A base class to define the interface to an implicit graph of convex sets. More...
|
| class | ImplicitGraphOfConvexSetsFromExplicit |
| | Provides an implicit GCS interface given an explicit GCS. More...
|
| class | Intersection |
| | A convex set that represents the intersection of multiple sets: S = X₁ ∩ X₂ ∩ ... ∩ Xₙ = {x | x ∈ X₁, x ∈ X₂, ..., x ∈ Xₙ}. More...
|
| struct | IrisOptions |
| | Configuration options for the IRIS algorithm. More...
|
| class | MinkowskiSum |
| | A convex set that represents the Minkowski sum of multiple sets: S = X₁ ⨁ X₂ ⨁ ... ⨁ Xₙ = {x₁ + x₂ + ... + xₙ | x₁ ∈ X₁, x₂ ∈ X₂, ..., xₙ ∈ Xₙ}. More...
|
| struct | PlaneSeparatesGeometries |
| | Contains the information to enforce a pair of geometries are separated by a plane. More...
|
| class | Point |
| | A convex set that contains exactly one element. More...
|
| struct | SampledVolume |
| | The result of a volume calculation from CalcVolumeViaSampling(). More...
|
| struct | SeparationCertificateProgramBase |
| struct | SeparationCertificateResultBase |
| | We certify that a pair of geometries is collision free by finding the separating plane over a range of configuration. More...
|
| class | Spectrahedron |
| | Implements a spectrahedron (the feasible set of a semidefinite program). More...
|
| class | VPolytope |
| | A polytope described using the vertex representation. More...
|
|
| double | DistanceToHalfspace (const CIrisCollisionGeometry &collision_geometry, const Eigen::Vector3d &a, double b, multibody::BodyIndex expressed_body, PlaneSide plane_side, const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context) |
| | Computes the signed distance from collision_geometry to the half space ℋ, where ℋ = {x | aᵀx+b >= 0} if plane_side=PlaneSide::kPositive, and ℋ = {x | aᵀx+b <= 0} if plane_side=PlaneSide::kNegative.
|
| template<typename... Args> |
| ConvexSets | MakeConvexSets (Args &&... args) |
| | Helper function that allows the ConvexSets to be initialized from arguments containing ConvexSet references, or unique_ptr<ConvexSet> instances, or any object that can be assigned to ConvexSets::value_type.
|
| SeparatingPlaneOrder | ToPlaneOrder (int plane_degree) |
| | Convert an integer degree to the SeparatingPlaneOrder.
|
| int | ToPlaneDegree (SeparatingPlaneOrder plane_order) |
| | Convert SeparatingPlaneOrder to an integer degree.
|
| template<typename D, typename S, typename V> |
| void | CalcPlane (const VectorX< D > &decision_variables, const VectorX< S > &s_for_plane, int plane_degree, Vector3< V > *a_val, V *b_val) |
| | Computes the parameters a, b in the plane { x | aᵀx+b=0 }.
|
| bool | CheckIfSatisfiesConvexityRadius (const geometry::optimization::ConvexSet &convex_set, const std::vector< int > &continuous_revolute_joints) |
| | Given a convex set, and a list of indices corresponding to continuous revolute joints, checks whether or not the set satisfies the convexity radius.
|
| geometry::optimization::ConvexSets | PartitionConvexSet (const geometry::optimization::ConvexSet &convex_set, const std::vector< int > &continuous_revolute_joints, const double epsilon=1e-5) |
| | Partitions a convex set into (smaller) convex sets whose union is the original set and that each respect the convexity radius as in CheckIfSatisfiesConvexityRadius.
|
| geometry::optimization::ConvexSets | PartitionConvexSet (const geometry::optimization::ConvexSets &convex_sets, const std::vector< int > &continuous_revolute_joints, const double epsilon=1e-5) |
| | Function overload to take in a list of convex sets, and partition all so as to respect the convexity radius.
|
| std::pair< std::vector< std::pair< int, int > >, std::vector< Eigen::VectorXd > > | ComputePairwiseIntersections (const ConvexSets &convex_sets_A, const ConvexSets &convex_sets_B, const std::vector< int > &continuous_revolute_joints, bool preprocess_bbox=true, Parallelism parallelism=Parallelism::Max()) |
| | Computes the pairwise intersections between two lists of convex sets, returning a list of edges, and a list of their corresponding offsets.
|
| std::pair< std::vector< std::pair< int, int > >, std::vector< Eigen::VectorXd > > | ComputePairwiseIntersections (const ConvexSets &convex_sets_A, const ConvexSets &convex_sets_B, const std::vector< int > &continuous_revolute_joints, const std::vector< geometry::optimization::Hyperrectangle > &bboxes_A, const std::vector< geometry::optimization::Hyperrectangle > &bboxes_B, Parallelism parallelism=Parallelism::Max()) |
| | Overload of ComputePairwiseIntersections allowing the user to supply axis- aligned bounding boxes if they're known a priori, to save on computation time.
|
| std::pair< std::vector< std::pair< int, int > >, std::vector< Eigen::VectorXd > > | ComputePairwiseIntersections (const ConvexSets &convex_sets, const std::vector< int > &continuous_revolute_joints, bool preprocess_bbox=true, Parallelism parallelism=Parallelism::Max()) |
| | Convenience overload to compute pairwise intersections within a list of convex sets.
|
| std::pair< std::vector< std::pair< int, int > >, std::vector< Eigen::VectorXd > > | ComputePairwiseIntersections (const ConvexSets &convex_sets, const std::vector< int > &continuous_revolute_joints, const std::vector< geometry::optimization::Hyperrectangle > &bboxes, Parallelism parallelism=Parallelism::Max()) |
| | Overload of ComputePairwiseIntersections allowing the user to supply axis- aligned bounding boxes if they're known a priori, to save on computation time.
|
| 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.
|
| Eigen::MatrixXd | GetVertices (const Convex &convex) |
| | Obtains all the vertices stored in the convex object.
|