Drake
Drake C++ Documentation
UnimplementedCollisionChecker Class Reference

Detailed Description

A concrete collision checker implementation that throws an exception for every virtual function hook.

This might be useful for unit testing or for deriving your own collision checker without providing for the full suite of operations.

#include <drake/planning/unimplemented_collision_checker.h>

Public Member Functions

 UnimplementedCollisionChecker (CollisionCheckerParams params, bool supports_parallel_checking)
 Constructs a checker. More...
 
 ~UnimplementedCollisionChecker ()
 
Does not allow copy, move, or assignment.
 UnimplementedCollisionChecker (UnimplementedCollisionChecker &&)=delete
 
UnimplementedCollisionCheckeroperator= (const UnimplementedCollisionChecker &)=delete
 
UnimplementedCollisionCheckeroperator= (UnimplementedCollisionChecker &&)=delete
 
- Public Member Functions inherited from CollisionChecker
virtual ~CollisionChecker ()
 
std::unique_ptr< CollisionCheckerClone () const
 
bool SupportsParallelChecking () const
 Does the collision checker support true parallel collision checks? More...
 
 CollisionChecker (CollisionChecker &&)=delete
 
CollisionCheckeroperator= (const CollisionChecker &)=delete
 
CollisionCheckeroperator= (CollisionChecker &&)=delete
 
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. More...
 
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 CollisionCheckerContextmodel_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. More...
 
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. More...
 
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. More...
 
const systems::Context< double > & UpdateContextPositions (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const
 Explicit Context-based version of UpdatePositions(). More...
 
std::shared_ptr< CollisionCheckerContextMakeStandaloneModelContext () const
 Make and track a CollisionCheckerContext. More...
 
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(). More...
 
bool AddCollisionShape (const std::string &group_name, const BodyShapeDescription &description)
 Requests the addition of a shape to a body, both given in description. More...
 
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. More...
 
std::map< std::string, intAddCollisionShapes (const std::map< std::string, std::vector< BodyShapeDescription >> &geometry_groups)
 Requests the addition of a collection of shapes to bodies across multiple geometry groups. More...
 
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. More...
 
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. More...
 
std::map< std::string, std::vector< BodyShapeDescription > > GetAllAddedCollisionShapes () const
 Gets all checker geometries currently added across the whole checker. More...
 
void RemoveAllAddedCollisionShapes (const std::string &group_name)
 Removes all added checker geometries which belong to the named group. More...
 
void RemoveAllAddedCollisionShapes ()
 Removes all added checker geometries from all geometry groups. More...
 
std::optional< doubleMaybeGetUniformRobotEnvironmentPadding () const
 If the padding between all robot bodies and environment bodies is the same, returns the common padding value. More...
 
std::optional< doubleMaybeGetUniformRobotRobotPadding () const
 If the padding between all pairs of robot bodies is the same, returns the common padding value. More...
 
double GetPaddingBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index) const
 Gets the padding value for the pair of bodies specified. More...
 
double GetPaddingBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB) const
 Overload that uses body references. More...
 
void SetPaddingBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index, double padding)
 Sets the padding value for the pair of bodies specified. More...
 
void SetPaddingBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB, double padding)
 Overload that uses body references. More...
 
const Eigen::MatrixXd & GetPaddingMatrix () const
 Gets the collision padding matrix. More...
 
void SetPaddingMatrix (const Eigen::MatrixXd &collision_padding)
 Sets the collision padding matrix. More...
 
double GetLargestPadding () const
 Gets the current largest collision padding across all (robot, *) body pairs. More...
 
void SetPaddingOneRobotBodyAllEnvironmentPairs (multibody::BodyIndex body_index, double padding)
 Sets the environment collision padding for the provided robot body with respect to all environment bodies. More...
 
void SetPaddingAllRobotEnvironmentPairs (double padding)
 Sets the padding for all (robot, environment) pairs. More...
 
void SetPaddingAllRobotRobotPairs (double padding)
 Sets the padding for all (robot, robot) pairs. More...
 
const Eigen::MatrixXi & GetNominalFilteredCollisionMatrix () const
 Returns the "nominal" collision filter matrix. More...
 
const Eigen::MatrixXi & GetFilteredCollisionMatrix () const
 Gets the "active" collision filter matrix. More...
 
void SetCollisionFilterMatrix (const Eigen::MatrixXi &filter_matrix)
 Sets the "active" collision filter matrix. More...
 
bool IsCollisionFilteredBetween (multibody::BodyIndex bodyA_index, multibody::BodyIndex bodyB_index) const
 Checks if collision is filtered between the two bodies specified. More...
 
bool IsCollisionFilteredBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB) const
 Overload that uses body references. More...
 
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. More...
 
void SetCollisionFilteredBetween (const multibody::RigidBody< double > &bodyA, const multibody::RigidBody< double > &bodyB, bool filter_collision)
 Overload that uses body references. More...
 
void SetCollisionFilteredWithAllBodies (multibody::BodyIndex body_index)
 Declares that body pair (B, O) is filtered (for all bodies O in this checker's plant). More...
 
void SetCollisionFilteredWithAllBodies (const multibody::RigidBody< double > &body)
 Overload that uses body references. More...
 
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. More...
 
bool CheckContextConfigCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const
 Explicit Context-based version of CheckConfigCollisionFree(). More...
 
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. More...
 
void SetDistanceAndInterpolationProvider (std::shared_ptr< const DistanceAndInterpolationProvider > provider)
 Sets the distance and interpolation provider to use. More...
 
const DistanceAndInterpolationProviderdistance_and_interpolation_provider () const
 Gets the DistanceAndInterpolationProvider in use. More...
 
void SetConfigurationDistanceFunction (const ConfigurationDistanceFunction &distance_function)
 Sets the configuration distance function to distance_function. More...
 
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(). More...
 
ConfigurationDistanceFunction MakeStandaloneConfigurationDistanceFunction () const
 
void SetConfigurationInterpolationFunction (const ConfigurationInterpolationFunction &interpolation_function)
 Sets the configuration interpolation function to interpolation_function. More...
 
Eigen::VectorXd InterpolateBetweenConfigurations (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, double ratio) const
 Interpolates between provided configurations q1 and q2. More...
 
ConfigurationInterpolationFunction MakeStandaloneConfigurationInterpolationFunction () const
 
double edge_step_size () const
 Gets the current edge step size. More...
 
void set_edge_step_size (double edge_step_size)
 Sets the edge step size to edge_step_size. More...
 
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. More...
 
bool CheckContextEdgeCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) const
 Explicit Context-based version of CheckEdgeCollisionFree(). More...
 
bool CheckEdgeCollisionFreeParallel (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, Parallelism parallelize=Parallelism::Max()) const
 Checks a single configuration-to-configuration edge for collision. More...
 
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. More...
 
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. More...
 
EdgeMeasure MeasureContextEdgeCollisionFree (CollisionCheckerContext *model_context, const Eigen::VectorXd &q1, const Eigen::VectorXd &q2) const
 Explicit Context-based version of MeasureEdgeCollisionFree(). More...
 
EdgeMeasure MeasureEdgeCollisionFreeParallel (const Eigen::VectorXd &q1, const Eigen::VectorXd &q2, Parallelism parallelize=Parallelism::Max()) const
 Checks a single configuration-to-configuration edge for collision. More...
 
std::vector< EdgeMeasureMeasureEdgesCollisionFree (const std::vector< std::pair< Eigen::VectorXd, Eigen::VectorXd >> &edges, Parallelism parallelize=Parallelism::Max()) const
 Checks multiple configuration-to-configuration edge for collision. More...
 
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. More...
 
RobotClearance CalcContextRobotClearance (CollisionCheckerContext *model_context, const Eigen::VectorXd &q, double influence_distance) const
 Explicit Context-based version of CalcRobotClearance(). More...
 
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. More...
 
int MaxContextNumDistances (const CollisionCheckerContext &model_context) const
 Explicit Context-based version of MaxNumDistances(). More...
 
std::vector< RobotCollisionTypeClassifyBodyCollisions (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. More...
 
std::vector< RobotCollisionTypeClassifyContextBodyCollisions (CollisionCheckerContext *model_context, const Eigen::VectorXd &q) const
 Explicit Context-based version of ClassifyBodyCollisions(). More...
 

Protected Member Functions

 UnimplementedCollisionChecker (const UnimplementedCollisionChecker &)
 
std::unique_ptr< CollisionCheckerDoClone () const override
 Derived collision checkers implement can make use of the protected copy constructor to implement DoClone(). More...
 
void DoUpdateContextPositions (CollisionCheckerContext *model_context) const override
 Derived collision checkers can do further work in this function in response to updates to the MultibodyPlant positions. More...
 
bool DoCheckContextConfigCollisionFree (const CollisionCheckerContext &) const override
 Derived collision checkers are responsible for reporting the collision status of the configuration. More...
 
std::optional< geometry::GeometryIdDoAddCollisionShapeToBody (const std::string &group_name, const multibody::RigidBody< double > &bodyA, const geometry::Shape &shape, const math::RigidTransform< double > &X_AG) override
 Does the work of adding a shape to be rigidly affixed to the body. More...
 
void RemoveAddedGeometries (const std::vector< CollisionChecker::AddedShape > &shapes) override
 Removes all of the given added shapes (if they exist) from the checker. More...
 
void UpdateCollisionFilters () override
 Derived collision checkers can do further work in this function in response to changes in collision filters. More...
 
RobotClearance DoCalcContextRobotClearance (const CollisionCheckerContext &, double) const override
 Derived collision checkers are responsible for defining the reported measurements. More...
 
std::vector< RobotCollisionTypeDoClassifyContextBodyCollisions (const CollisionCheckerContext &) const override
 Derived collision checkers are responsible for choosing a collision type for each of the robot bodies. More...
 
int DoMaxContextNumDistances (const CollisionCheckerContext &) const override
 Derived collision checkers must implement the semantics documented for MaxNumDistances. More...
 
- Protected Member Functions inherited from CollisionChecker
 CollisionChecker (CollisionCheckerParams params, bool supports_parallel_checking)
 Derived classes declare upon construction whether they support parallel checking (see SupportsParallelChecking()). More...
 
 CollisionChecker (const CollisionChecker &)
 To support Clone(), allow copying (but not move nor assign). More...
 
void AllocateContexts ()
 Allocate the per-thread context pool, and discontinue mutable access to the robot model. More...
 
virtual std::unique_ptr< CollisionCheckerContextCreatePrototypeContext () const
 Collision checkers that use derived context types can override this implementation to allocate their context type instead. More...
 
bool IsInitialSetup () const
 
RobotDiagram< double > & GetMutableSetupModel ()
 
bool CanEvaluateInParallel () const
 
std::string CriticizePaddingMatrix () const
 

Constructor & Destructor Documentation

◆ UnimplementedCollisionChecker() [1/3]

UnimplementedCollisionChecker ( CollisionCheckerParams  params,
bool  supports_parallel_checking 
)

Constructs a checker.

Parameters
supports_parallel_checkingwill serve as the return value of the CollisionChecker::SupportsParallelChecking() function.

◆ UnimplementedCollisionChecker() [2/3]

◆ ~UnimplementedCollisionChecker()

◆ UnimplementedCollisionChecker() [3/3]

Member Function Documentation

◆ DoAddCollisionShapeToBody()

std::optional<geometry::GeometryId> DoAddCollisionShapeToBody ( const std::string &  group_name,
const multibody::RigidBody< double > &  bodyA,
const geometry::Shape shape,
const math::RigidTransform< double > &  X_AG 
)
overrideprotectedvirtual

Does the work of adding a shape to be rigidly affixed to the body.

Derived checkers can choose to ignore the request, but must return nullopt if they do so.

Implements CollisionChecker.

◆ DoCalcContextRobotClearance()

RobotClearance DoCalcContextRobotClearance ( const CollisionCheckerContext model_context,
double  influence_distance 
) const
overrideprotectedvirtual

Derived collision checkers are responsible for defining the reported measurements.

But they must adhere to the characteristics documented on RobotClearance, e.g., one measurement per row. CollisionChecker guarantees that influence_distance is finite and non-negative.

Implements CollisionChecker.

◆ DoCheckContextConfigCollisionFree()

bool DoCheckContextConfigCollisionFree ( const CollisionCheckerContext model_context) const
overrideprotectedvirtual

Derived collision checkers are responsible for reporting the collision status of the configuration.

CollisionChecker guarantees that the passed model_context has been updated with the configuration q supplied to the public method.

Implements CollisionChecker.

◆ DoClassifyContextBodyCollisions()

std::vector<RobotCollisionType> DoClassifyContextBodyCollisions ( const CollisionCheckerContext model_context) const
overrideprotectedvirtual

Derived collision checkers are responsible for choosing a collision type for each of the robot bodies.

They should adhere to the semantics documented for ClassifyBodyCollisions. CollisionChecker guarantees that the passed model_context has been updated with the configuration q supplied to the public method.

Implements CollisionChecker.

◆ DoClone()

std::unique_ptr<CollisionChecker> DoClone ( ) const
overrideprotectedvirtual

Derived collision checkers implement can make use of the protected copy constructor to implement DoClone().

Implements CollisionChecker.

◆ DoMaxContextNumDistances()

int DoMaxContextNumDistances ( const CollisionCheckerContext model_context) const
overrideprotectedvirtual

Derived collision checkers must implement the semantics documented for MaxNumDistances.

CollisionChecker does nothing; it just calls this method.

Implements CollisionChecker.

◆ DoUpdateContextPositions()

void DoUpdateContextPositions ( CollisionCheckerContext model_context) const
overrideprotectedvirtual

Derived collision checkers can do further work in this function in response to updates to the MultibodyPlant positions.

CollisionChecker guarantees that model_context will not be nullptr and that the new positions are present in model_context->plant_context().

Implements CollisionChecker.

◆ operator=() [1/2]

◆ operator=() [2/2]

◆ RemoveAddedGeometries()

void RemoveAddedGeometries ( const std::vector< CollisionChecker::AddedShape > &  shapes)
overrideprotectedvirtual

Removes all of the given added shapes (if they exist) from the checker.

Implements CollisionChecker.

◆ UpdateCollisionFilters()

void UpdateCollisionFilters ( )
overrideprotectedvirtual

Derived collision checkers can do further work in this function in response to changes in collision filters.

This is called after any changes are made to the collision filter matrix.

Implements CollisionChecker.


The documentation for this class was generated from the following file: