37 #ifndef MOVEIT_COLLISION_DETECTION_FCL_COLLISION_WORLD_FCL_ 38 #define MOVEIT_COLLISION_DETECTION_FCL_COLLISION_WORLD_FCL_ 43 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0)) 44 #include <fcl/broadphase/broadphase_collision_manager.h> 46 #include <fcl/broadphase/broadphase.h> 80 void setWorld(
const WorldPtr& world)
override;
91 std::unique_ptr<fcl::BroadPhaseCollisionManagerd>
manager_;
Representation of a distance-reporting request.
Representation of a collision checking request.
void updateFCLObject(const std::string &id)
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const override
Compute the distance between a robot and the world.
~CollisionWorldFCL() override
void distanceWorld(const DistanceRequest &req, DistanceResult &res, const CollisionWorld &world) const override
Compute the distance between another world.
void checkWorldCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world, const AllowedCollisionMatrix *acm) const
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Representation of a collision checking result.
void setWorld(const WorldPtr &world) override
std::unique_ptr< fcl::BroadPhaseCollisionManagerd > manager_
Generic interface to collision detection.
World::ObjectConstPtr ObjectConstPtr
void checkRobotCollision(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state) const override
Check whether the robot model is in collision with the world. Any collisions between a robot link and...
A representation of an object.
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
void constructFCLObject(const World::Object *obj, FCLObject &fcl_obj) const
This class represents a collision model of the robot and can be used for self collision checks (to ch...
Result of a distance request.
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const CollisionRobot &robot, const robot_state::RobotState &state, const AllowedCollisionMatrix *acm) const
Perform collision checking with the environment. The collision world maintains a representation of th...
Representation of a robot's state. This includes position, velocity, acceleration and effort...
void notifyObjectChange(const ObjectConstPtr &obj, World::Action action)
World::ObserverHandle observer_handle_
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
void checkWorldCollision(const CollisionRequest &req, CollisionResult &res, const CollisionWorld &other_world) const override
Check whether a given set of objects is in collision with objects from another world. Any contacts are considered.
std::map< std::string, FCLObject > fcl_objs_