43 #include <geometric_shapes/check_isometry.h>
45 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
46 #include <fcl/broadphase/broadphase_collision_manager.h>
47 #include <fcl/narrowphase/collision.h>
48 #include <fcl/narrowphase/distance.h>
50 #include <fcl/broadphase/broadphase.h>
51 #include <fcl/collision.h>
52 #include <fcl/distance.h>
86 const std::string&
getID()
const
91 return ptr.link->getName();
93 return ptr.ab->getName();
108 return "Robot attached";
157 void enableGroup(
const moveit::core::RobotModelConstPtr& robot_model);
233 template <
typename T>
271 std::shared_ptr<fcl::BroadPhaseCollisionManagerd>
manager_;
324 #if (MOVEIT_FCL_VERSION >= FCL_VERSION_CHECK(0, 6, 0))
327 Eigen::Quaterniond q(b.linear());
328 f.setTranslation(
fcl::Vector3d(b.translation().x(), b.translation().y(), b.translation().z()));
329 f.setQuatRotation(fcl::Quaternion3f(q.w(), q.x(), q.y(), q.z()));
346 c.depth = fc.penetration_depth;
348 c.body_name_1 = cgd1->
getID();
349 c.body_type_1 = cgd1->
type;
351 c.body_name_2 = cgd2->
getID();
352 c.body_type_2 = cgd2->
type;
366 cs.
cost = fcs.cost_density;
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
Object defining bodies that can be attached to robot links.
A link from the robot. Contains the constant transform applied to the link and its geometry.
Type
The types of bodies that are considered for collision.
@ ROBOT_LINK
A link on the robot.
@ ROBOT_ATTACHED
A body attached to a robot link.
@ WORLD_OBJECT
A body in the environment.
MOVEIT_STRUCT_FORWARD(CollisionGeometryData)
void fcl2contact(const fcl::Contactd &fc, Contact &c)
Transforms an FCL contact into a MoveIt contact point.
FCLGeometryConstPtr createCollisionGeometry(const shapes::ShapeConstPtr &shape, const moveit::core::LinkModel *link, int shape_index)
Create new FCLGeometry object out of robot link model.
void cleanCollisionGeometryCache()
Increases the counter of the caches which can trigger the cleaning of expired entries from them.
bool collisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
Callback function used by the FCLManager used for each pair of collision objects to calculate object ...
std::shared_ptr< fcl::CollisionObjectd > FCLCollisionObjectPtr
void transform2fcl(const Eigen::Isometry3d &b, fcl::Transform3d &f)
Transforms an Eigen Isometry3d to FCL coordinate transformation.
std::shared_ptr< const fcl::CollisionObjectd > FCLCollisionObjectConstPtr
void fcl2costsource(const fcl::CostSourced &fcs, CostSource &cs)
Transforms the FCL internal representation to the MoveIt CostSource data structure.
bool distanceCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &min_dist)
Callback function used by the FCLManager used for each pair of collision objects to calculate collisi...
Vec3fX< details::Vec3Data< double > > Vector3d
fcl::CollisionObject CollisionObjectd
fcl::BroadPhaseCollisionManager BroadPhaseCollisionManagerd
fcl::CostSource CostSourced
fcl::CollisionGeometry CollisionGeometryd
fcl::Transform3f Transform3d
Data structure which is passed to the collision callback function of the collision manager.
const std::set< const moveit::core::LinkModel * > * active_components_only_
If the collision request includes a group name, this set contains the pointers to the link models tha...
CollisionData(const CollisionRequest *req, CollisionResult *res, const AllowedCollisionMatrix *acm)
const AllowedCollisionMatrix * acm_
The user-specified collision matrix (may be nullptr).
void enableGroup(const moveit::core::RobotModelConstPtr &robot_model)
Compute active_components_only_ based on the joint group specified in req_.
bool done_
Flag indicating whether collision checking is complete.
CollisionResult * res_
The user-specified response location.
const CollisionRequest * req_
The collision request passed by the user.
Wrapper around world, link and attached objects' geometry data.
const moveit::core::LinkModel * link
CollisionGeometryData(const moveit::core::AttachedBody *ab, int index)
Constructor for a new collision geometry object which is attached to the robot.
bool sameObject(const CollisionGeometryData &other) const
Check if two CollisionGeometryData objects point to the same source object.
const std::string & getID() const
Returns the name which is saved in the member pointed to in ptr.
CollisionGeometryData(const moveit::core::LinkModel *link, int index)
Constructor for a robot link collision geometry object.
int shape_index
Multiple CollisionGeometryData objects construct a collision object. The collision object refers to a...
CollisionGeometryData(const World::Object *obj, int index)
Constructor for a new world collision geometry.
std::string getTypeString() const
Returns a string of the corresponding type.
const moveit::core::AttachedBody * ab
union collision_detection::CollisionGeometryData::@0 ptr
Points to the type of body which contains the geometry.
const World::Object * obj
BodyType type
Indicates the body type of the object.
Representation of a collision checking request.
Representation of a collision checking result.
When collision costs are computed, this structure contains information about the partial cost incurre...
std::array< double, 3 > aabb_max
The maximum bound of the AABB defining the volume responsible for this partial cost.
double cost
The partial cost (the probability of existence for the object there is a collision with)
std::array< double, 3 > aabb_min
The minimum bound of the AABB defining the volume responsible for this partial cost.
Data structure which is passed to the distance callback function of the collision manager.
DistanceResult * res
Distance query results information.
const DistanceRequest * req
Distance query request information.
DistanceData(const DistanceRequest *req, DistanceResult *res)
bool done
Indicates if distance query is finished.
Representation of a distance-reporting request.
Result of a distance request.
Bundles the CollisionGeometryData and FCL collision geometry representation into a single class.
CollisionGeometryDataPtr collision_geometry_data_
Pointer to the user-defined geometry data.
FCLGeometry(fcl::CollisionGeometryd *collision_geometry, const moveit::core::AttachedBody *ab, int shape_index)
Constructor for an attached body.
std::shared_ptr< fcl::CollisionGeometryd > collision_geometry_
Pointer to FCL collision geometry.
FCLGeometry(fcl::CollisionGeometryd *collision_geometry, const World::Object *obj, int shape_index)
Constructor for a world object.
FCLGeometry(fcl::CollisionGeometryd *collision_geometry, const moveit::core::LinkModel *link, int shape_index)
Constructor for a robot link.
void updateCollisionGeometryData(const T *data, int shape_index, bool newType)
Updates the collision_geometry_data_ with new data while also setting the collision_geometry_ to the ...
Bundles an FCLObject and a broadphase FCL collision manager.
std::shared_ptr< fcl::BroadPhaseCollisionManagerd > manager_
A general high-level object which consists of multiple FCLCollisionObjects. It is the top level data ...
std::vector< FCLCollisionObjectPtr > collision_objects_
void unregisterFrom(fcl::BroadPhaseCollisionManagerd *manager)
std::vector< FCLGeometryConstPtr > collision_geometry_
Geometry data corresponding to collision_objects_.
void registerTo(fcl::BroadPhaseCollisionManagerd *manager)
A representation of an object.