37 #ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ 38 #define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ 95 std::vector<FCLGeometryConstPtr>
geoms_;
void allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const
Representation of a distance-reporting request.
Representation of a collision checking request.
Core components of MoveIt!
void getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
Check for collision with a different robot (possibly a different kinematic model as well)...
Bundles an FCLObject and a broadphase FCL collision manager.
Representation of a collision checking result.
std::vector< FCLGeometryConstPtr > geoms_
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
When the scale or padding is changed for a set of links by any of the functions in this class...
Generic interface to collision detection.
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::vector< FCLCollisionObjectConstPtr > fcl_objs_
CollisionRobotFCL(const robot_model::RobotModelConstPtr &robot_model, double padding=0.0, double scale=1.0)
Result of a distance request.
void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const override
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
void checkOtherCollisionHelper(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state, const AllowedCollisionMatrix *acm) const
void distanceSelf(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state) const override
The distance to self-collision given the robot is at state state.
Representation of a robot's state. This includes position, velocity, acceleration and effort...
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
void distanceOther(const DistanceRequest &req, DistanceResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const override
The distance to self-collision given the robot is at state state.
void constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const