30 #ifndef EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_ 31 #define EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_ 36 #include <fcl/BVH/BVH_model.h> 37 #include <fcl/broadphase/broadphase.h> 38 #include <fcl/collision.h> 39 #include <fcl/distance.h> 40 #include <fcl/narrowphase/narrowphase.h> 41 #include <fcl/octree.h> 42 #include <fcl/shape/geometric_shapes.h> 62 void Setup()
override;
65 static bool CollisionCallback(fcl::CollisionObject* o1, fcl::CollisionObject* o2,
void* data);
85 void UpdateCollisionObjects(
const std::map<std::string, std::weak_ptr<KinematicElement>>& objects)
override;
94 std::map<std::string, std::shared_ptr<fcl::CollisionObject>>
fcl_cache_;
101 #endif // EXOTICA_COLLISION_SCENE_FCL_COLLISION_SCENE_FCL_H_
void UpdateCollisionObjectTransforms() override
Updates collision object transformations from the kinematic tree.
CollisionSceneFCL * scene
CollisionData(CollisionSceneFCL *scene_in)
std::shared_ptr< fcl::CollisionObject > ConstructFclCollisionObject(long i, std::shared_ptr< KinematicElement > element)
fcl::CollisionResult result
std::vector< std::weak_ptr< KinematicElement > > kinematic_elements_
std::map< std::string, std::shared_ptr< fcl::CollisionObject > > fcl_cache_
static bool CollisionCallback(fcl::CollisionObject *o1, fcl::CollisionObject *o2, void *data)
std::vector< std::string > GetCollisionRobotLinks() override
Gets the collision robot links.
std::vector< std::string > GetCollisionWorldLinks() override
Gets the collision world links.
void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects) override
Creates the collision scene from kinematic elements.
std::vector< fcl::CollisionObject * > fcl_objects_
fcl::CollisionRequest request
Eigen::Vector3d GetTranslation(const std::string &name) override
bool IsCollisionFree(const std::string &o1, const std::string &o2, double safe_distance=0.0) override
bool IsStateValid(bool self=true, double safe_distance=0.0) override
Check if the whole robot is valid (collision only).
static bool IsAllowedToCollide(fcl::CollisionObject *o1, fcl::CollisionObject *o2, bool self, CollisionSceneFCL *scene)
static void CheckCollision(fcl::CollisionObject *o1, fcl::CollisionObject *o2, CollisionData *data)