An implementation of CollisionChecker that uses SceneGraph to provide collision checks.
Its behavior and limitations are exactly those of SceneGraph, e.g., in terms of what kinds of geometries can be collided.
|
| | SceneGraphCollisionChecker (CollisionCheckerParams params) |
| | Creates a new checker with the given params.
|
| void | operator= (const SceneGraphCollisionChecker &)=delete |
| | CollisionChecker (CollisionChecker &&)=delete |
| CollisionChecker & | operator= (const CollisionChecker &)=delete |
| CollisionChecker & | operator= (CollisionChecker &&)=delete |
| virtual | ~CollisionChecker () |
| std::unique_ptr< CollisionChecker > | Clone () const |
| const RobotDiagram< double > & | model () const |
| const multibody::MultibodyPlant< double > & | plant () const |
| const multibody::RigidBody< double > & | get_body (multibody::BodyIndex body_index) const |
| const std::vector< multibody::ModelInstanceIndex > & | robot_model_instances () const |
| | Gets the set of model instances belonging to the robot.
|
| bool | IsPartOfRobot (const multibody::RigidBody< double > &body) const |
| bool | IsPartOfRobot (multibody::BodyIndex body_index) const |
| const Eigen::VectorXd & | GetZeroConfiguration () const |
| int | num_allocated_contexts () const |
| const CollisionCheckerContext & | model_context (std::optional< int > context_number=std::nullopt) const |
| | Accesses a collision checking context from within the implicit context pool owned by this collision checker.
|
| const systems::Context< double > & | plant_context (std::optional< int > context_number=std::nullopt) const |
| | Accesses a multibody plant sub-context context from within the implicit context pool owned by this collision checker.
|
| const systems::Context< double > & | UpdatePositions (const Eigen::VectorXd &q, std::optional< int > context_number=std::nullopt) const |
| | Updates the generalized positions q in the implicit context specified and returns a reference to the MultibodyPlant's now-updated context.
|
| const systems::Context< double > & | UpdateContextPositions (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const |
| | Explicit Context-based version of UpdatePositions().
|
| std::shared_ptr< CollisionCheckerContext > | MakeStandaloneModelContext () const |
| | Make and track a CollisionCheckerContext.
|
| void | PerformOperationAgainstAllModelContexts (const std::function< void(const RobotDiagram< double > &, CollisionCheckerContext *)> &operation) |
| | Allows externally-provided operations that must be performed against all contexts in the per-thread context pool, and any standalone contexts made with MakeStandaloneModelContext().
|
| bool | AddCollisionShape (const std::string &group_name, const BodyShapeDescription &description) |
| | Requests the addition of a shape to a body, both given in description.
|
| int | AddCollisionShapes (const std::string &group_name, const std::vector< BodyShapeDescription > &descriptions) |
| | Requests the addition of N shapes to N bodies, each given in the set of descriptions.
|
| std::map< std::string, int > | AddCollisionShapes (const std::map< std::string, std::vector< BodyShapeDescription > > &geometry_groups) |
| | Requests the addition of a collection of shapes to bodies across multiple geometry groups.
|
| bool | AddCollisionShapeToFrame (const std::string &group_name, const multibody::Frame< double > &frameA, const geometry::Shape &shape, const math::RigidTransform< double > &X_AG) |
| | Requests the addition of shape to the frame A in the checker's model.
|
| bool | AddCollisionShapeToBody (const std::string &group_name, const multibody::RigidBody< double > &bodyA, const geometry::Shape &shape, const math::RigidTransform< double > &X_AG) |
| | Requests the addition of shape to the body A in the checker's model The added shape will belong to the named geometry group.
|
| std::map< std::string, std::vector< BodyShapeDescription > > | GetAllAddedCollisionShapes () const |
| | Gets all checker geometries currently added across the whole checker.
|
| void | RemoveAllAddedCollisionShapes (const std::string &group_name) |
| | Removes all added checker geometries which belong to the named group.
|
| void | RemoveAllAddedCollisionShapes () |
| | Removes all added checker geometries from all geometry groups.
|
| std::optional< double > | MaybeGetUniformRobotEnvironmentPadding () const |
| | If the padding between all robot bodies and environment bodies is the same, returns the common padding value.
|
| std::optional< double > | MaybeGetUniformRobotRobotPadding () const |
| | If the padding between all pairs of robot bodies is the same, returns the common padding value.
|
| double | GetPaddingBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index) const |
| | Gets the padding value for the pair of bodies specified.
|
| double | GetPaddingBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB) const |
| | Overload that uses body references.
|
| void | SetPaddingBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index, double padding) |
| | Sets the padding value for the pair of bodies specified.
|
| void | SetPaddingBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB, double padding) |
| | Overload that uses body references.
|
| const Eigen::MatrixXd & | GetPaddingMatrix () const |
| | Gets the collision padding matrix.
|
| void | SetPaddingMatrix (const Eigen::MatrixXd &collision_padding) |
| | Sets the collision padding matrix.
|
| double | GetLargestPadding () const |
| | Gets the current largest collision padding across all (robot, *) body pairs.
|
| void | SetPaddingOneRobotBodyAllEnvironmentPairs (multibody::BodyIndex body_index, double padding) |
| | Sets the environment collision padding for the provided robot body with respect to all environment bodies.
|
| void | SetPaddingAllRobotEnvironmentPairs (double padding) |
| | Sets the padding for all (robot, environment) pairs.
|
| void | SetPaddingAllRobotRobotPairs (double padding) |
| | Sets the padding for all (robot, robot) pairs.
|
| const Eigen::MatrixXi & | GetNominalFilteredCollisionMatrix () const |
| | Returns the "nominal" collision filter matrix.
|
| const Eigen::MatrixXi & | GetFilteredCollisionMatrix () const |
| | Gets the "active" collision filter matrix.
|
| void | SetCollisionFilterMatrix (const Eigen::MatrixXi &filter_matrix) |
| | Sets the "active" collision filter matrix.
|
| bool | IsCollisionFilteredBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index) const |
| | Checks if collision is filtered between the two bodies specified.
|
| bool | IsCollisionFilteredBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB) const |
| | Overload that uses body references.
|
| void | SetCollisionFilteredBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index, bool filter_collision) |
| | Declares the body pair (bodyA, bodyB) to be filtered (or not) based on filter_collision.
|
| void | SetCollisionFilteredBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB, bool filter_collision) |
| | Overload that uses body references.
|
| void | SetCollisionFilteredWithAllBodies (multibody::BodyIndex body_index) |
| | Declares that body pair (B, O) is filtered (for all bodies O in this checker's plant).
|
| void | SetCollisionFilteredWithAllBodies (const multibody::RigidBody< double > &body) |
| | Overload that uses body references.
|
| bool | CheckConfigCollisionFree (const Eigen::VectorXd &q, std::optional< int > context_number=std::nullopt) const |
| | Checks a single configuration for collision using the current thread's associated context.
|
| bool | CheckContextConfigCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const |
| | Explicit Context-based version of CheckConfigCollisionFree().
|
| std::vector< uint8_t > | CheckConfigsCollisionFree (const std::vector< Eigen::VectorXd > &configs, Parallelism parallelize=Parallelism::Max()) const |
| | Checks a vector of configurations for collision, evaluating in parallel when supported and enabled by parallelize.
|
| void | SetDistanceAndInterpolationProvider (std::shared_ptr< const DistanceAndInterpolationProvider > provider) |
| | Sets the distance and interpolation provider to use.
|
| const DistanceAndInterpolationProvider & | distance_and_interpolation_provider () const |
| | Gets the DistanceAndInterpolationProvider in use.
|
| void | SetConfigurationDistanceFunction (const ConfigurationDistanceFunction &distance_function) |
| | Sets the configuration distance function to distance_function.
|
| double | ComputeConfigurationDistance (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) const |
| | Computes configuration-space distance between the provided configurations q1 and q2, using the distance function configured at construction- time or via SetConfigurationDistanceFunction().
|
| ConfigurationDistanceFunction | MakeStandaloneConfigurationDistanceFunction () const |
| void | SetConfigurationInterpolationFunction (const ConfigurationInterpolationFunction &interpolation_function) |
| | Sets the configuration interpolation function to interpolation_function.
|
| Eigen::VectorXd | InterpolateBetweenConfigurations (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, double ratio) const |
| | Interpolates between provided configurations q1 and q2.
|
| ConfigurationInterpolationFunction | MakeStandaloneConfigurationInterpolationFunction () const |
| double | edge_step_size () const |
| | Gets the current edge step size.
|
| void | set_edge_step_size (double edge_step_size) |
| | Sets the edge step size to edge_step_size.
|
| bool | CheckEdgeCollisionFree (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, std::optional< int > context_number=std::nullopt) const |
| | Checks a single configuration-to-configuration edge for collision, using the current thread's associated context.
|
| bool | CheckContextEdgeCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) const |
| | Explicit Context-based version of CheckEdgeCollisionFree().
|
| bool | CheckEdgeCollisionFreeParallel (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, Parallelism parallelize=Parallelism::Max()) const |
| | Checks a single configuration-to-configuration edge for collision.
|
| std::vector< uint8_t > | CheckEdgesCollisionFree (const std::vector< std::pair< Eigen::VectorXd, Eigen::VectorXd > > &edges, Parallelism parallelize=Parallelism::Max()) const |
| | Checks multiple configuration-to-configuration edges for collision.
|
| EdgeMeasure | MeasureEdgeCollisionFree (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, std::optional< int > context_number=std::nullopt) const |
| | Checks a single configuration-to-configuration edge for collision, using the current thread's associated context.
|
| EdgeMeasure | MeasureContextEdgeCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) const |
| | Explicit Context-based version of MeasureEdgeCollisionFree().
|
| EdgeMeasure | MeasureEdgeCollisionFreeParallel (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, Parallelism parallelize=Parallelism::Max()) const |
| | Checks a single configuration-to-configuration edge for collision.
|
| std::vector< EdgeMeasure > | MeasureEdgesCollisionFree (const std::vector< std::pair< Eigen::VectorXd, Eigen::VectorXd > > &edges, Parallelism parallelize=Parallelism::Max()) const |
| | Checks multiple configuration-to-configuration edge for collision.
|
| RobotClearance | CalcRobotClearance (const Eigen::VectorXd &q, double influence_distance, std::optional< int > context_number=std::nullopt) const |
| | Calculates the distance, ϕ, and distance Jacobian, Jqᵣ_ϕ, for each potential collision whose distance is less than influence_distance, using the current thread's associated context.
|
| RobotClearance | CalcContextRobotClearance (CollisionCheckerContext *model_context, const Eigen::VectorXd &q, double influence_distance) const |
| | Explicit Context-based version of CalcRobotClearance().
|
| int | MaxNumDistances (std::optional< int > context_number=std::nullopt) const |
| | Returns an upper bound on the number of distances returned by CalcRobotClearance(), using the current thread's associated context.
|
| int | MaxContextNumDistances (const CollisionCheckerContext &model_context) const |
| | Explicit Context-based version of MaxNumDistances().
|
| std::vector< RobotCollisionType > | ClassifyBodyCollisions (const Eigen::VectorXd &q, std::optional< int > context_number=std::nullopt) const |
| | Classifies which robot bodies are in collision (and which type of collision) for the provided configuration q, using the current thread's associated context.
|
| std::vector< RobotCollisionType > | ClassifyContextBodyCollisions (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const |
| | Explicit Context-based version of ClassifyBodyCollisions().
|
| bool | SupportsParallelChecking () const |
| | Does the collision checker support true parallel collision checks?
|