37 #ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ 38 #define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_ROBOT_ 49 CollisionRobotFCL(
const robot_model::RobotModelConstPtr& kmodel,
double padding = 0.0,
double scale = 1.0);
98 std::vector<FCLGeometryConstPtr>
geoms_;
Representation of a collision checking request.
void constructFCLObject(const robot_state::RobotState &state, FCLObject &fcl_obj) const
virtual void checkOtherCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state, const CollisionRobot &other_robot, const robot_state::RobotState &other_state) const
Check for collision with a different robot (possibly a different kinematic model as well)...
CollisionRobotFCL(const robot_model::RobotModelConstPtr &kmodel, double padding=0.0, double scale=1.0)
Representation of a collision checking result.
void allocSelfCollisionBroadPhase(const robot_state::RobotState &state, FCLManager &manager) const
std::vector< FCLGeometryConstPtr > geoms_
Generic interface to collision detection.
virtual void checkSelfCollision(const CollisionRequest &req, CollisionResult &res, const robot_state::RobotState &state) const
Check for self collision. Any collision between any pair of links is checked for, NO collisions are i...
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...
void getAttachedBodyObjects(const robot_state::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
This class represents a collision model of the robot and can be used for self collision checks (to ch...
std::vector< FCLCollisionObjectConstPtr > fcl_objs_
virtual 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...
virtual void updatedPaddingOrScaling(const std::vector< std::string > &links)
When the scale or padding is changed for a set of links by any of the functions in this class...
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
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
virtual 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.