Go to the documentation of this file.
30 #ifndef EXOTICA_COLLISION_SCENE_FCL_LATEST_COLLISION_SCENE_FCL_LATEST_H_
31 #define EXOTICA_COLLISION_SCENE_FCL_LATEST_COLLISION_SCENE_FCL_LATEST_H_
38 #include <exotica_collision_scene_fcl_latest/collision_scene_fcl_latest_initializer.h>
68 void Setup()
override;
70 bool IsAllowedToCollide(
const std::string& o1,
const std::string& o2,
const bool&
self)
override;
73 static bool CollisionCallback(fcl::CollisionObjectd* o1, fcl::CollisionObjectd* o2,
void* data);
79 bool IsStateValid(
bool self =
true,
double safe_distance = 0.0)
override;
80 bool IsCollisionFree(
const std::string& o1,
const std::string& o2,
double safe_distance = 0.0)
override;
86 std::vector<CollisionProxy>
GetCollisionDistance(
const std::string& o1,
const std::string& o2)
override;
87 std::vector<CollisionProxy>
GetCollisionDistance(
const std::string& o1,
const bool&
self =
true)
override;
88 std::vector<CollisionProxy>
GetCollisionDistance(
const std::vector<std::string>& objects,
const bool&
self =
true)
override;
89 std::vector<CollisionProxy>
GetCollisionDistance(
const std::string& o1,
const bool&
self =
true,
const bool& disable_collision_scene_update =
false)
override;
116 void UpdateCollisionObjects(
const std::map<std::string, std::weak_ptr<KinematicElement>>& objects)
override;
129 std::vector<std::shared_ptr<fcl::CollisionObjectd>>
fcl_cache_;
143 return it->second.lock();
172 #endif // EXOTICA_COLLISION_SCENE_FCL_LATEST_COLLISION_SCENE_FCL_LATEST_H_
Definition: collision_scene_fcl_latest.h:57
std::shared_ptr< KinematicElement > GetKinematicElementFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:138
Definition: distance.h:39
CollisionSceneFCLLatest * scene
Definition: collision_scene_fcl_latest.h:52
std::vector< std::string > GetCollisionRobotLinks() override
Gets the collision robot links.
Definition: collision_scene.h:87
double safe_distance
Definition: collision_scene_fcl_latest.h:54
ContinuousCollisionProxy ContinuousCollisionCheck(const std::string &o1, const KDL::Frame &tf1_beg, const KDL::Frame &tf1_end, const std::string &o2, const KDL::Frame &tf2_beg, const KDL::Frame &tf2_end) override
Performs a continuous collision check between two objects with a linear interpolation between two giv...
static void ComputeDistance(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, DistanceData *data)
std::shared_ptr< fcl::CollisionObjectd > ConstructFclCollisionObject(long i, std::shared_ptr< KinematicElement > element)
std::vector< CollisionProxy > proxies
Definition: collision_scene_fcl_latest.h:63
std::shared_ptr< fcl::BroadPhaseCollisionManagerd > broad_phase_collision_manager_
Definition: collision_scene_fcl_latest.h:122
std::map< std::string, std::weak_ptr< KinematicElement > > kinematic_elements_map_
Definition: collision_scene_fcl_latest.h:131
void UpdateCollisionObjects(const std::map< std::string, std::weak_ptr< KinematicElement >> &objects) override
Creates the collision scene from kinematic elements.
Definition: collision_scene_fcl_latest.h:47
std::vector< CollisionProxy > GetRobotToWorldCollisionDistance(double check_margin) override
Gets the closest distances between links of the robot and the environment that are closer than check_...
DistanceData(CollisionSceneFCLLatest *scene_in)
Definition: collision_scene_fcl_latest.h:59
Definition: property.h:110
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_world_objects_map_
Definition: collision_scene_fcl_latest.h:136
Definition: cartpole_dynamics_solver.h:38
CollisionSceneFCLLatest * scene
Definition: collision_scene_fcl_latest.h:62
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_robot_objects_map_
Definition: collision_scene_fcl_latest.h:135
fcl::CollisionResultd result
Definition: collision_scene_fcl_latest.h:51
std::vector< std::weak_ptr< KinematicElement > > kinematic_elements_
Definition: collision_scene_fcl_latest.h:130
std::vector< fcl::CollisionObjectd * > GetCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:162
bool IsAllowedToCollide(const std::string &o1, const std::string &o2, const bool &self) override
Returns whether two collision objects/shapes are allowed to collide by name.
void Setup() override
Setup additional construction that requires initialiser parameter.
Definition: collision_scene_fcl_latest.h:44
void UpdateCollisionObjectTransforms() override
Updates collision object transformations from the kinematic tree.
std::map< std::string, std::vector< fcl::CollisionObjectd * > > fcl_objects_map_
Definition: collision_scene_fcl_latest.h:134
static bool CollisionCallbackDistance(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &dist)
std::vector< std::shared_ptr< fcl::CollisionObjectd > > fcl_cache_
Definition: collision_scene_fcl_latest.h:129
fcl::DistanceRequestd request
Definition: collision_scene_fcl_latest.h:60
Eigen::Vector3d GetTranslation(const std::string &name) override
Returns the translation of the named collision object.
static bool CollisionCallback(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
std::vector< fcl::CollisionObjectd * > GetRobotCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:146
std::vector< std::string > GetCollisionWorldLinks() override
Gets the collision world links.
The class of collision scene.
Definition: collision_scene.h:148
fcl::DistanceResultd result
Definition: collision_scene_fcl_latest.h:61
std::vector< CollisionProxy > GetCollisionDistance(bool self) override
Computes collision distances.
#define ThrowPretty(m)
Definition: exception.h:36
fcl::CollisionRequestd request
Definition: collision_scene_fcl_latest.h:50
CollisionData(CollisionSceneFCLLatest *scene_in)
Definition: collision_scene_fcl_latest.h:49
bool IsCollisionFree(const std::string &o1, const std::string &o2, double safe_distance=0.0) override
Checks if two objects are in collision.
static void CheckCollision(fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, CollisionData *data)
std::vector< fcl::CollisionObjectd * > GetWorldCollisionObjectsFromMapByName(const std::string &frame_name)
Definition: collision_scene_fcl_latest.h:154
std::vector< fcl::CollisionObjectd * > fcl_objects_
Definition: collision_scene_fcl_latest.h:128
bool IsStateValid(bool self=true, double safe_distance=0.0) override
Check if the whole robot is valid (collision only).
std::vector< CollisionProxy > GetRobotToRobotCollisionDistance(double check_margin) override
Gets the closest distances between links within the robot that are closer than check_margin.