42#if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
43#include <fcl/broadphase/broadphase_collision_manager.h>
45#include <fcl/broadphase/broadphase.h>
58 CollisionEnvFCL(
const moveit::core::RobotModelConstPtr& model,
double padding = 0.0,
double scale = 1.0);
60 CollisionEnvFCL(
const moveit::core::RobotModelConstPtr& model,
const WorldPtr& world,
double padding = 0.0,
91 void setWorld(
const WorldPtr& world)
override;
149 std::unique_ptr<fcl::BroadPhaseCollisionManagerd>
manager_;
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
FCL implementation of the CollisionEnv.
std::vector< FCLCollisionObjectConstPtr > robot_fcl_objs_
Vector of shared pointers to the FCL collision objects which make up the robot.
void constructFCLObjectRobot(const moveit::core::RobotState &state, FCLObject &fcl_obj) const
Out of the current robot state and its attached bodies construct an FCLObject which can then be used ...
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 setWorld(const WorldPtr &world) override
std::unique_ptr< fcl::BroadPhaseCollisionManagerd > manager_
FCL collision manager which handles the collision checking process.
void distanceRobot(const DistanceRequest &req, DistanceResult &res, const moveit::core::RobotState &state) const override
Compute the distance between a robot and the world.
void checkRobotCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkRobotCollision functions into a single function.
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.
void updatedPaddingOrScaling(const std::vector< std::string > &links) override
Updates the FCL collision geometry and objects saved in the CollisionRobotFCL members to reflect a ne...
void allocSelfCollisionBroadPhase(const moveit::core::RobotState &state, FCLManager &manager) const
Prepares for the collision check through constructing an FCL collision object out of the current robo...
void updateFCLObject(const std::string &id)
Updates the specified object in \m fcl_objs_ and in the manager from new data available in the World.
void constructFCLObjectWorld(const World::Object *obj, FCLObject &fcl_obj) const
Construct an FCL collision object from MoveIt's World::Object.
~CollisionEnvFCL() override
void checkSelfCollisionHelper(const CollisionRequest &req, CollisionResult &res, const moveit::core::RobotState &state, const AllowedCollisionMatrix *acm) const
Bundles the different checkSelfCollision functions into a single function.
std::vector< FCLGeometryConstPtr > robot_geoms_
Vector of shared pointers to the FCL geometry for the objects in fcl_objs_.
std::map< std::string, FCLObject > fcl_objs_
void getAttachedBodyObjects(const moveit::core::AttachedBody *ab, std::vector< FCLGeometryConstPtr > &geoms) const
Converts all shapes which make up an attached body into a vector of FCLGeometryConstPtr.
Provides the interface to the individual collision checking libraries.
World::ObjectConstPtr ObjectConstPtr
Represents an action that occurred on an object in the world. Several bits may be set indicating seve...
Object defining bodies that can be attached to robot links.
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.
Bundles an FCLObject and a broadphase FCL collision manager.
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
A representation of an object.