Drake
Drake C++ Documentation
Loading...
Searching...
No Matches
SphereRobotModelCollisionChecker Class Referenceabstract

Detailed Description

Base class for collision checkers using a sphere-geometry robot model.

Derived classes must implement distance and gradient checks against environment geometry. Note: this class is designed such that derived classes can support copy/move/assignment.

#include <drake/planning/experimental/sphere_robot_model_collision_checker.h>

Public Member Functions

void UpdateBodyCollisionModel (multibody::BodyIndex body_index, const std::vector< SphereSpecification > &spheres, bool append)
 Update the sphere collision model of a specific body of the robot.
const std::vector< BodySpheres > & RobotCollisionModel () const
 Get a reference to the internal collision model of the robot.
std::string GetURDFCollisionGeometriesForRobotCollisionModel () const
 Generates the URDF <collision> elements corresponding to the robot's collision model.
bool CheckSelfCollisionFree (const std::vector< Eigen::Isometry3d > &X_WB_set) const
 Check if the robot is in self-collision.
std::vector< Eigen::Isometry3d > ComputeBodyPoses (const Eigen::VectorXd &q, std::optional< int > context_number=std::nullopt) const
 Compute pose of all bodies, using the current thread's context.
std::vector< Eigen::Isometry3d > GetBodyPoses (const systems::Context< double > &plant_context) const
 Get pose of all bodies.
std::vector< BodySpheresComputeSphereLocationsInWorldFrame (const std::vector< Eigen::Isometry3d > &X_WB_set) const
 Compute sphere collision model in world frame.
std::vector< BodySpheresComputeSphereLocationsInWorldFrame (const Eigen::VectorXd &q, std::optional< int > context_number=std::nullopt) const
 Compute sphere collision model in world frame, using the current thread's context.
const std::unordered_set< geometry::GeometryId > & RobotGeometries () const
virtual PointSignedDistanceAndGradientResult ComputePointToEnvironmentSignedDistanceAndGradient (const systems::Context< double > &context, const geometry::QueryObject< double > &query_object, const Eigen::Vector4d &p_WQ, double query_radius, const std::vector< Eigen::Isometry3d > &X_WB_set, const std::vector< Eigen::Isometry3d > &X_WB_inverse_set) const =0
 Query the (distance, gradient) of the provided point from obstacles.
virtual PointSignedDistanceAndGradientResult ComputePointToEnvironmentSignedDistance (const systems::Context< double > &context, const geometry::QueryObject< double > &query_object, const Eigen::Vector4d &p_WQ, double query_radius, const std::vector< Eigen::Isometry3d > &X_WB_set, const std::vector< Eigen::Isometry3d > &X_WB_inverse_set) const
 Query the distance of the provided point from obstacles.
PointSignedDistanceAndGradientResult ComputeSelfCollisionSignedDistanceAndGradient (const std::vector< BodySpheres > &spheres_in_world_frame, multibody::BodyIndex query_body_index, geometry::GeometryId query_sphere_id, double influence_distance) const
Does not allow copy, move, or assignment.
void operator= (const SphereRobotModelCollisionChecker &)=delete
Public Member Functions inherited from CollisionChecker
 CollisionChecker (CollisionChecker &&)=delete
CollisionCheckeroperator= (const CollisionChecker &)=delete
CollisionCheckeroperator= (CollisionChecker &&)=delete
virtual ~CollisionChecker ()
std::unique_ptr< CollisionCheckerClone () 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 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.
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< CollisionCheckerContextMakeStandaloneModelContext () 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 DistanceAndInterpolationProviderdistance_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< EdgeMeasureMeasureEdgesCollisionFree (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< 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.
std::vector< RobotCollisionTypeClassifyContextBodyCollisions (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?

Protected Member Functions

 SphereRobotModelCollisionChecker (CollisionCheckerParams params)
 Construct a base collision checker for sphere-geometry robot models.
 SphereRobotModelCollisionChecker (const SphereRobotModelCollisionChecker &)
 To support Clone(), allow copying (but not move nor assign).
virtual std::optional< geometry::GeometryIdAddEnvironmentCollisionShapeToBody (const std::string &group_name, const multibody::Body< double > &bodyA, const geometry::Shape &shape, const math::RigidTransform< double > &X_AG)=0
virtual void RemoveAllAddedEnvironment (const std::vector< CollisionChecker::AddedShape > &shapes)=0
virtual std::optional< double > EstimateConservativePointToEnvironmentSignedDistance (const systems::Context< double > &context, const geometry::QueryObject< double > &query_object, const Eigen::Vector4d &p_WQ, double query_radius, const std::vector< Eigen::Isometry3d > &X_WB_set, const std::vector< Eigen::Isometry3d > &X_WB_inverse_set) const =0
 Query a conservative underestimate of the distance of the provided point from obstacles.
virtual std::unique_ptr< CollisionCheckerDoClone () const =0
 Derived collision checkers implement can make use of the protected copy constructor to implement DoClone().
virtual std::optional< geometry::GeometryIdDoAddCollisionShapeToBody (const std::string &group_name, const multibody::RigidBody< double > &bodyA, const geometry::Shape &shape, const math::RigidTransform< double > &X_AG)=0
 Does the work of adding a shape to be rigidly affixed to the body.
bool CanEvaluateInParallel () const
std::string CriticizePaddingMatrix () const
 CollisionChecker (CollisionCheckerParams params, bool supports_parallel_checking)
 Derived classes declare upon construction whether they support parallel checking (see SupportsParallelChecking()).
 CollisionChecker (const CollisionChecker &)
 To support Clone(), allow copying (but not move nor assign).
void AllocateContexts ()
 Allocate the per-thread context pool, and discontinue mutable access to the robot model.
virtual std::unique_ptr< CollisionCheckerContextCreatePrototypeContext () const
 Collision checkers that use derived context types can override this implementation to allocate their context type instead.
bool IsInitialSetup () const
RobotDiagram< double > & GetMutableSetupModel ()

Constructor & Destructor Documentation

◆ SphereRobotModelCollisionChecker() [1/2]

SphereRobotModelCollisionChecker ( CollisionCheckerParams params)
explicitprotected

Construct a base collision checker for sphere-geometry robot models.

◆ SphereRobotModelCollisionChecker() [2/2]

SphereRobotModelCollisionChecker ( const SphereRobotModelCollisionChecker & )
explicitprotected

To support Clone(), allow copying (but not move nor assign).

Member Function Documentation

◆ AddEnvironmentCollisionShapeToBody()

virtual std::optional< geometry::GeometryId > AddEnvironmentCollisionShapeToBody ( const std::string & group_name,
const multibody::Body< double > & bodyA,
const geometry::Shape & shape,
const math::RigidTransform< double > & X_AG )
protectedpure virtual

◆ CheckSelfCollisionFree()

bool CheckSelfCollisionFree ( const std::vector< Eigen::Isometry3d > & X_WB_set) const

Check if the robot is in self-collision.

Parameters
X_WB_setVector of X_WB, pose of robot body B in world W.
Returns
true if self-collision free, false otherwise.

◆ ComputeBodyPoses()

std::vector< Eigen::Isometry3d > ComputeBodyPoses ( const Eigen::VectorXd & q,
std::optional< int > context_number = std::nullopt ) const

Compute pose of all bodies, using the current thread's context.

Parameters
qConfiguration to compute poses for.
Returns
Vector of X_WB, pose of body B in world W, for all bodies.

◆ ComputePointToEnvironmentSignedDistance()

virtual PointSignedDistanceAndGradientResult ComputePointToEnvironmentSignedDistance ( const systems::Context< double > & context,
const geometry::QueryObject< double > & query_object,
const Eigen::Vector4d & p_WQ,
double query_radius,
const std::vector< Eigen::Isometry3d > & X_WB_set,
const std::vector< Eigen::Isometry3d > & X_WB_inverse_set ) const
virtual

Query the distance of the provided point from obstacles.

Parameters
contextContext of the MbP model.
query_objectQuery object for context.
p_WQQuery position in world frame W.
query_radiusGradients do not need to be computed for queries with distance > query_radius. This parameter is needed because the default implementation calls ComputePointSignedDistanceAndGradient, and only needing to check within a bound can improve performance.
X_WB_setPoses X_WB for all bodies in the model. This is used to move gradients from signed distance fields back to world frame.
X_WB_inverse_setPoses X_BW for all bodies in the model. This is useful for some implementations to move the provided p_WQ into a different body frame.
Returns
signed distances where signed distance is positive if p_WQ is outside of objects, and negative if it is inside. The default implementation here is always sufficient, but in some cases, it may be faster for an implementation to only compute the distance, rather than the distance gradient. Since the binary collision checking methods only need distance, we want them to be as fast as possible. Note that queries farther than query_radius from collision need not return exact distance.

Reimplemented in VoxelizedEnvironmentCollisionChecker.

◆ ComputePointToEnvironmentSignedDistanceAndGradient()

virtual PointSignedDistanceAndGradientResult ComputePointToEnvironmentSignedDistanceAndGradient ( const systems::Context< double > & context,
const geometry::QueryObject< double > & query_object,
const Eigen::Vector4d & p_WQ,
double query_radius,
const std::vector< Eigen::Isometry3d > & X_WB_set,
const std::vector< Eigen::Isometry3d > & X_WB_inverse_set ) const
pure virtual

Query the (distance, gradient) of the provided point from obstacles.

Parameters
contextContext of the MbP model.
query_objectQuery object for context.
p_WQQuery position in world frame W.
query_radiusGradients do not need to be computed for queries with distance > query radius. This allows for faster performance by reducing the number of gradients to compute as well as reducing the number of gradients this method returns.
X_WB_setPoses X_WB for all bodies in the model. This is used to move gradients from signed distance fields back to world frame.
X_WB_inverse_setPoses X_BW for all bodies in the model. This is useful for some implementations to move the provided p_WQ into a different body frame.
Returns
signed distances and gradients where signed distance is positive if p_WQ is outside of objects, and negative if it is inside. The gradient is ∂d/∂p. Note that queries farther than query_radius from collision need not return exact distance.

Implemented in MbpEnvironmentCollisionChecker, and VoxelizedEnvironmentCollisionChecker.

◆ ComputeSelfCollisionSignedDistanceAndGradient()

PointSignedDistanceAndGradientResult ComputeSelfCollisionSignedDistanceAndGradient ( const std::vector< BodySpheres > & spheres_in_world_frame,
multibody::BodyIndex query_body_index,
geometry::GeometryId query_sphere_id,
double influence_distance ) const

◆ ComputeSphereLocationsInWorldFrame() [1/2]

std::vector< BodySpheres > ComputeSphereLocationsInWorldFrame ( const Eigen::VectorXd & q,
std::optional< int > context_number = std::nullopt ) const

Compute sphere collision model in world frame, using the current thread's context.

Parameters
qConfiguration to compute poses for.
Returns
Vector of link sphere models.

◆ ComputeSphereLocationsInWorldFrame() [2/2]

std::vector< BodySpheres > ComputeSphereLocationsInWorldFrame ( const std::vector< Eigen::Isometry3d > & X_WB_set) const

Compute sphere collision model in world frame.

Parameters
X_WB_setBody poses to use.
Returns
Vector of link sphere models.

◆ EstimateConservativePointToEnvironmentSignedDistance()

virtual std::optional< double > EstimateConservativePointToEnvironmentSignedDistance ( const systems::Context< double > & context,
const geometry::QueryObject< double > & query_object,
const Eigen::Vector4d & p_WQ,
double query_radius,
const std::vector< Eigen::Isometry3d > & X_WB_set,
const std::vector< Eigen::Isometry3d > & X_WB_inverse_set ) const
protectedpure virtual

Query a conservative underestimate of the distance of the provided point from obstacles.

Parameters
contextContext of the MbP model.
query_objectQuery object for context.
p_WQQuery position in world frame W.
query_radiusIf no obstacles are within this distance of p_WQ, infinity (or any value greater than query_radius) may be returned to avoid the work of computing a more exact distance.
X_WB_setPoses X_WB for all bodies in the model. This is used to move gradients from signed distance fields back to world frame.
X_WB_inverse_setPoses X_BW for all bodies in the model. This is useful for some implementations to move the provided p_WQ into a different body frame.
Returns
a conservative underestimate of the distance between the provided point p_WQ and obstacles. If no such estimate is possible, nullopt must be returned.

◆ GetBodyPoses()

std::vector< Eigen::Isometry3d > GetBodyPoses ( const systems::Context< double > & plant_context) const

Get pose of all bodies.

Parameters
plant_contextMbP context, already updated, to use.
Returns
Vector of X_WB, pose of body B in world W, for all bodies.

◆ GetURDFCollisionGeometriesForRobotCollisionModel()

std::string GetURDFCollisionGeometriesForRobotCollisionModel ( ) const

Generates the URDF <collision> elements corresponding to the robot's collision model.

◆ operator=()

void operator= ( const SphereRobotModelCollisionChecker & )
delete

◆ RemoveAllAddedEnvironment()

virtual void RemoveAllAddedEnvironment ( const std::vector< CollisionChecker::AddedShape > & shapes)
protectedpure virtual

◆ RobotCollisionModel()

const std::vector< BodySpheres > & RobotCollisionModel ( ) const

Get a reference to the internal collision model of the robot.

◆ RobotGeometries()

const std::unordered_set< geometry::GeometryId > & RobotGeometries ( ) const

◆ UpdateBodyCollisionModel()

void UpdateBodyCollisionModel ( multibody::BodyIndex body_index,
const std::vector< SphereSpecification > & spheres,
bool append )

Update the sphere collision model of a specific body of the robot.

Parameters
body_indexIndex of the body (body 0 is world).
spheresSphere geometry to add to the collision model.
appendIf true, appends the spheres to the existing model, otherwise the new model replaces the existing model. Note: changes to the collision model here do not go through the added geometry mechanism.

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