Go to the documentation of this file.
44 static const std::string
NAME =
"ALL_VALID";
54 double padding,
double scale)
60 : CollisionEnv(other, world)
67 res.collision =
false;
69 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
74 const AllowedCollisionMatrix& )
const
76 res.collision =
false;
78 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
87 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
97 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
112 const AllowedCollisionMatrix& )
const
122 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
131 ROS_INFO_NAMED(
"collision_detection",
"Using AllValid collision detection. No collision checking is performed.");
Core components of MoveIt.
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...
const std::string & getName() const override
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Representation of a collision checking request.
Definition of a structure for the allowed collision matrix.
static const std::string NAME
CollisionEnvAllValid(const moveit::core::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
#define ROS_INFO_NAMED(name,...)
Representation of a collision checking result.
bool verbose
Flag indicating whether information about detected collisions should be reported.
bool collision
Indicates if two objects were in collision.
Result of a distance request.
bool collision
True if collision was found, false otherwise.
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.
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,...
Representation of a distance-reporting request.
virtual double distanceRobot(const moveit::core::RobotState &state) const
moveit_core
Author(s): Ioan Sucan
, Sachin Chitta , Acorn Pooley
autogenerated on Sun Nov 3 2024 03:26:14