Namespaces | |
| namespace | graph_algorithms |
| namespace | trajectory_optimization |
Classes | |
| class | BodyShapeDescription |
| BodyShapeDescription captures all the information necessary to describe a SceneGraph collision shape associated with a MultibodyPlant Body: a shape S, the MultibodyPlant body B (identified by model instance and body names), and the rigid pose of the shape S relative to the body B, X_BS. More... | |
| class | CollisionChecker |
| Interface for collision checkers to use. More... | |
| class | CollisionCheckerContext |
| This class represents the data necessary for CollisionChecker to operate safely across multiple threads in its const API. More... | |
| struct | CollisionCheckerParams |
| A set of common constructor parameters for a CollisionChecker. More... | |
| class | CommonSampledIrisOptions |
| Various options which are common to the sampling-based algorithms IrisNp2 and IrisZo for generating collision free polytopes in configuration space. More... | |
| class | DistanceAndInterpolationProvider |
| This class represents the base interface for performing configuration distance and interpolation operations, used by CollisionChecker. More... | |
| class | DofMask |
| A mask on the degrees of freedom (dofs) of a MultibodyPlant instance, partitioning the plant's dofs into "selected" and "unselected" dofs. More... | |
| class | EdgeMeasure |
| The measure of the distance of the edge from q1 to q2 and the portion of that is collision free. More... | |
| struct | IrisFromCliqueCoverOptions |
| class | IrisNp2Options |
| IrisNp2Options collects all parameters for the IRIS-NP2 algorithm. More... | |
| class | IrisParameterizationFunction |
| Ordinarily, IRIS algorithms grow collision free regions in the robot's configuration space C. More... | |
| class | IrisZoOptions |
| IrisZoOptions collects all parameters for the IRIS-ZO algorithm. More... | |
| class | JointLimits |
| Wrapper type for position, velocity, and acceleration limits. More... | |
| class | LinearDistanceAndInterpolationProvider |
| This class represents a basic "linear" implementation of DistanceAndInterpolationProvider. More... | |
| struct | RaySamplerOptions |
| RaySamplerOptions contains settings specific to the kRaySampler strategy for drawing the initial samples. More... | |
| class | RobotClearance |
| A summary of the clearance – a collection of distance measurements – between the robot and everything in the world. More... | |
| class | RobotDiagram |
| Storage for a combined diagram, plant, and scene graph. More... | |
| class | RobotDiagramBuilder |
| Storage for a combined diagram builder, plant, and scene graph. More... | |
| class | SceneGraphCollisionChecker |
| An implementation of CollisionChecker that uses SceneGraph to provide collision checks. More... | |
| class | UnimplementedCollisionChecker |
| A concrete collision checker implementation that throws an exception for every virtual function hook. More... | |
| class | ZmpPlanner |
| Given a desired two dimensional (X and Y) zero-moment point (ZMP) trajectory parameterized as a piecewise polynomial, an optimal center of mass (CoM) trajectory is planned using a linear inverted pendulum model (LIPM). More... | |
Typedefs | |
| using | ConfigurationDistanceFunction |
| Configuration distance takes two configurations of the robot, q1 and q2, both as Eigen::VectorXd, and returns (potentially weighted) C-space distance as a double. | |
| using | ConfigurationInterpolationFunction |
| Configuration interpolation function takes two configurations of the robot, q1, and q2, both as Eigen::VectorXd, plus a ratio, r, in [0, 1] and returns the interpolated configuration. | |
Enumerations | |
| enum class | RobotCollisionType : uint8_t { kNoCollision = 0x00 , kEnvironmentCollision = 0x01 , kSelfCollision = 0x02 , kEnvironmentAndSelfCollision = kEnvironmentCollision | kSelfCollision } |
| Enumerates these predicates (and their combinations): More... | |
Functions | |
| BodyShapeDescription | MakeBodyShapeDescription (const multibody::MultibodyPlant< double > &plant, const systems::Context< double > &plant_context, const geometry::GeometryId &geometry_id) |
| Constructs a BodyShapeDescription by extracting the shape, pose, and names associated with the provided geometry_id. | |
| void | IrisInConfigurationSpaceFromCliqueCover (const CollisionChecker &checker, const IrisFromCliqueCoverOptions &options, RandomGenerator *generator, std::vector< geometry::optimization::HPolyhedron > *sets, const planning::graph_algorithms::MaxCliqueSolverBase *max_clique_solver=nullptr) |
| Cover the configuration space in Iris regions using the Visibility Clique Cover Algorithm as described in. | |
| geometry::optimization::HPolyhedron | IrisNp2 (const SceneGraphCollisionChecker &checker, const geometry::optimization::Hyperellipsoid &starting_ellipsoid, const geometry::optimization::HPolyhedron &domain, const IrisNp2Options &options=IrisNp2Options()) |
| The IRIS-NP2 (Iterative Regional Inflation by Semidefinite and Nonlinear Programming 2) algorithm, as described in. | |
| geometry::optimization::HPolyhedron | IrisZo (const CollisionChecker &checker, const geometry::optimization::Hyperellipsoid &starting_ellipsoid, const geometry::optimization::HPolyhedron &domain, const IrisZoOptions &options=IrisZoOptions()) |
| The IRIS-ZO (Iterative Regional Inflation by Semidefinite programming - Zero Order) algorithm, as described in. | |
| RobotCollisionType | SetInEnvironmentCollision (RobotCollisionType collision_type, bool in_environment_collision) |
| RobotCollisionType | SetInSelfCollision (RobotCollisionType collision_type, bool in_self_collision) |
| Eigen::SparseMatrix< bool > | VisibilityGraph (const CollisionChecker &checker, const Eigen::Ref< const Eigen::MatrixXd > &points, Parallelism parallelize=Parallelism::Max()) |
| Given some number of sampled points in the configuration space of checker's plant(), computes the "visibility graph" – two points have an edge between them if the line segment connecting them is collision free. | |
Configuration distance takes two configurations of the robot, q1 and q2, both as Eigen::VectorXd, and returns (potentially weighted) C-space distance as a double.
The returned distance will be strictly non-negative.
To be valid, the function must satisfy the following condition:
for values of q that are valid for the CollisionChecker's plant.
Configuration interpolation function takes two configurations of the robot, q1, and q2, both as Eigen::VectorXd, plus a ratio, r, in [0, 1] and returns the interpolated configuration.
Behavior of the function for values of r outside of the range [0,1] is undefined.
To be valid, the function must satisfy the following conditions:
for values of q, q1, and q2 that are valid for the CollisionChecker's plant.
| BodyShapeDescription MakeBodyShapeDescription | ( | const multibody::MultibodyPlant< double > & | plant, |
| const systems::Context< double > & | plant_context, | ||
| const geometry::GeometryId & | geometry_id ) |
Constructs a BodyShapeDescription by extracting the shape, pose, and names associated with the provided geometry_id.
plant_context is compatible with plant. plant is connected to a scene graph. geometry_id refers to a geometry rigidly affixed to a body of plant. | RobotCollisionType SetInEnvironmentCollision | ( | RobotCollisionType | collision_type, |
| bool | in_environment_collision ) |
| RobotCollisionType SetInSelfCollision | ( | RobotCollisionType | collision_type, |
| bool | in_self_collision ) |
| Eigen::SparseMatrix< bool > VisibilityGraph | ( | const CollisionChecker & | checker, |
| const Eigen::Ref< const Eigen::MatrixXd > & | points, | ||
| Parallelism | parallelize = Parallelism::Max() ) |
Given some number of sampled points in the configuration space of checker's plant(), computes the "visibility graph" – two points have an edge between them if the line segment connecting them is collision free.
See CollisionChecker documentation for more information on how edge collision checks are performed.
Note that this method assumes the collision checker has symmetric behavior (i.e. checking edge (q1, q2) is the same as checking edge (q2, q1)). This is true for many collision checkers (e.g. those using LinearDistanceAndInterpolationProvider, which is the default), but some more complex spaces with non-linear interpolation (e.g. a Dubin's car) are not symmetric.
If parallelize specifies more than one thread, then the CollisionCheckerParams::distance_and_interpolation_provider for checker must be implemented in C++, either by providing the C++ implementation directly directly or by using the default provider.