49 CollisionEnvAllValid(
const moveit::core::RobotModelConstPtr& robot_model,
double padding = 0.0,
double scale = 1.0);
50 CollisionEnvAllValid(
const moveit::core::RobotModelConstPtr& robot_model,
const WorldPtr& world,
double padding = 0.0,
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Collision environment which always just returns no collisions.
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check for robot self collision. Any collision between any pair of links is checked for,...
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
The distance to self-collision given the robot is at state state.
virtual double distanceRobot(const moveit::core::RobotState &state) const
Provides the interface to the individual collision checking libraries.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Representation of a collision checking request.
Representation of a collision checking result.
Representation of a distance-reporting request.
Result of a distance request.