A set of common constructor parameters for a CollisionChecker.
Not all subclasses of CollisionChecker will necessarily support this configuration struct, but many do so.
#include <drake/planning/collision_checker_params.h>
Public Attributes | |
std::unique_ptr< RobotDiagram< double > > | model |
A RobotDiagram model of the robot and environment. More... | |
std::shared_ptr< const DistanceAndInterpolationProvider > | distance_and_interpolation_provider |
A DistanceAndInterpolationProvider to support configuration distance and interpolation operations. More... | |
std::vector< drake::multibody::ModelInstanceIndex > | robot_model_instances |
A vector of model instance indices that identify which model instances belong to the robot. More... | |
ConfigurationDistanceFunction | configuration_distance_function |
Configuration (probably weighted) distance function. More... | |
double | edge_step_size {} |
Step size for edge checking; in units compatible with the configuration distance function. More... | |
double | env_collision_padding {} |
Additional padding to apply to all robot-environment collision queries. More... | |
double | self_collision_padding {} |
Additional padding to apply to all robot-robot self collision queries. More... | |
Parallelism | implicit_context_parallelism = Parallelism::Max() |
Specify how many contexts should be allocated to support collision checker implicit context parallelism. More... | |
ConfigurationDistanceFunction configuration_distance_function |
Configuration (probably weighted) distance function.
configuration_distance_function
object will be copied and retained by a collision checker, so if the function has any lambda-captured data then that data must outlive the collision checker. std::shared_ptr<const DistanceAndInterpolationProvider> distance_and_interpolation_provider |
A DistanceAndInterpolationProvider to support configuration distance and interpolation operations.
double edge_step_size {} |
Step size for edge checking; in units compatible with the configuration distance function.
Collision checking of edges q1->q2 is performed by interpolating from q1 to q2 at edge_step_size steps and checking the interpolated configuration for collision. The value must be positive.
double env_collision_padding {} |
Additional padding to apply to all robot-environment collision queries.
If distance between robot and environment is less than padding, the checker reports a collision.
Parallelism implicit_context_parallelism = Parallelism::Max() |
Specify how many contexts should be allocated to support collision checker implicit context parallelism.
Defaults to the maximum parallelism. If the specific collision checker type in use declares that it does not support parallel queries, then implicit context parallelism is set to None().
std::unique_ptr<RobotDiagram<double> > model |
A RobotDiagram model of the robot and environment.
Must not be nullptr.
std::vector<drake::multibody::ModelInstanceIndex> robot_model_instances |
A vector of model instance indices that identify which model instances belong to the robot.
The list must be non-empty and must not include the world model instance.
double self_collision_padding {} |
Additional padding to apply to all robot-robot self collision queries.
If distance between robot and itself is less than padding, the checker reports a collision.