#include <collision_scene_fcl_latest.h>

| Classes | |
| struct | CollisionData | 
| struct | DistanceData | 
| Public Member Functions | |
| 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 given.  More... | |
| std::vector< CollisionProxy > | GetCollisionDistance (bool self) override | 
| Computes collision distances.  More... | |
| std::vector< CollisionProxy > | GetCollisionDistance (const std::string &o1, const std::string &o2) override | 
| std::vector< CollisionProxy > | GetCollisionDistance (const std::string &o1, const bool &self=true) override | 
| std::vector< CollisionProxy > | GetCollisionDistance (const std::vector< std::string > &objects, const bool &self=true) override | 
| std::vector< CollisionProxy > | GetCollisionDistance (const std::string &o1, const bool &self=true, const bool &disable_collision_scene_update=false) override | 
| std::vector< std::string > | GetCollisionRobotLinks () override | 
| Gets the collision robot links.  More... | |
| std::vector< std::string > | GetCollisionWorldLinks () override | 
| Gets the collision world links.  More... | |
| std::vector< CollisionProxy > | GetRobotToRobotCollisionDistance (double check_margin) override | 
| std::vector< CollisionProxy > | GetRobotToWorldCollisionDistance (double check_margin) override | 
| Eigen::Vector3d | GetTranslation (const std::string &name) override | 
| bool | IsAllowedToCollide (const std::string &o1, const std::string &o2, const bool &self) 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).  More... | |
| void | Setup () override | 
| void | UpdateCollisionObjects (const std::map< std::string, std::weak_ptr< KinematicElement >> &objects) override | 
| Creates the collision scene from kinematic elements.  More... | |
| void | UpdateCollisionObjectTransforms () override | 
| Updates collision object transformations from the kinematic tree.  More... | |
|  Public Member Functions inherited from exotica::CollisionScene | |
| void | AssignScene (std::shared_ptr< Scene > scene) | 
| CollisionScene () | |
| virtual std::vector< ContinuousCollisionProxy > | ContinuousCollisionCast (const std::vector< std::vector< std::tuple< std::string, Eigen::Isometry3d, Eigen::Isometry3d >>> &motion_transforms) | 
| bool | get_replace_cylinders_with_capsules () const | 
| bool | GetAlwaysExternallyUpdatedCollisionScene () const | 
| bool | GetReplacePrimitiveShapesWithMeshes () const | 
| double | GetRobotLinkPadding () const | 
| double | GetRobotLinkScale () const | 
| double | GetWorldLinkPadding () const | 
| double | GetWorldLinkScale () const | 
| virtual void | InstantiateBase (const Initializer &init) | 
| void | set_replace_cylinders_with_capsules (const bool value) | 
| void | SetACM (const AllowedCollisionMatrix &acm) | 
| void | SetAlwaysExternallyUpdatedCollisionScene (const bool value) | 
| void | SetReplacePrimitiveShapesWithMeshes (const bool value) | 
| void | SetRobotLinkPadding (const double padding) | 
| void | SetRobotLinkScale (const double scale) | 
| void | SetWorldLinkPadding (const double padding) | 
| void | SetWorldLinkScale (const double scale) | 
| virtual | ~CollisionScene () | 
|  Public Member Functions inherited from exotica::Object | |
| std::string | GetObjectName () | 
| void | InstantiateObject (const Initializer &init) | 
| Object () | |
| virtual std::string | Print (const std::string &prepend) const | 
| virtual std::string | type () const | 
| virtual | ~Object () | 
|  Public Member Functions inherited from exotica::Uncopyable | |
| Uncopyable ()=default | |
| ~Uncopyable ()=default | |
|  Public Member Functions inherited from exotica::InstantiableBase | |
| InstantiableBase ()=default | |
| virtual | ~InstantiableBase ()=default | 
|  Public Member Functions inherited from exotica::Instantiable< CollisionSceneFCLLatestInitializer > | |
| std::vector< Initializer > | GetAllTemplates () const override | 
| Initializer | GetInitializerTemplate () override | 
| const CollisionSceneFCLLatestInitializer & | GetParameters () const | 
| virtual void | Instantiate (const CollisionSceneFCLLatestInitializer &init) | 
| void | InstantiateInternal (const Initializer &init) override | 
| Static Public Member Functions | |
| static bool | CollisionCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data) | 
| static bool | CollisionCallbackDistance (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &dist) | 
| static bool | IsAllowedToCollide (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, bool self, CollisionSceneFCLLatest *scene) | 
| Private Member Functions | |
| std::shared_ptr< fcl::CollisionObjectd > | ConstructFclCollisionObject (long i, std::shared_ptr< KinematicElement > element) | 
| std::vector< fcl::CollisionObjectd * > | GetCollisionObjectsFromMapByName (const std::string &frame_name) | 
| std::shared_ptr< KinematicElement > | GetKinematicElementFromMapByName (const std::string &frame_name) | 
| std::vector< fcl::CollisionObjectd * > | GetRobotCollisionObjectsFromMapByName (const std::string &frame_name) | 
| std::vector< fcl::CollisionObjectd * > | GetWorldCollisionObjectsFromMapByName (const std::string &frame_name) | 
| Static Private Member Functions | |
| static void | CheckCollision (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, CollisionData *data) | 
| static void | ComputeDistance (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, DistanceData *data) | 
| Private Attributes | |
| std::shared_ptr< fcl::BroadPhaseCollisionManagerd > | broad_phase_collision_manager_ | 
| std::vector< std::shared_ptr< fcl::CollisionObjectd > > | fcl_cache_ | 
| std::vector< fcl::CollisionObjectd * > | fcl_objects_ | 
| std::map< std::string, std::vector< fcl::CollisionObjectd * > > | fcl_objects_map_ | 
| std::map< std::string, std::vector< fcl::CollisionObjectd * > > | fcl_robot_objects_map_ | 
| std::map< std::string, std::vector< fcl::CollisionObjectd * > > | fcl_world_objects_map_ | 
| std::vector< std::weak_ptr< KinematicElement > > | kinematic_elements_ | 
| std::map< std::string, std::weak_ptr< KinematicElement > > | kinematic_elements_map_ | 
| Additional Inherited Members | |
|  Public Attributes inherited from exotica::CollisionScene | |
| bool | debug_ | 
|  Public Attributes inherited from exotica::Object | |
| bool | debug_ | 
| std::string | ns_ | 
| std::string | object_name_ | 
|  Protected Attributes inherited from exotica::CollisionScene | |
| AllowedCollisionMatrix | acm_ | 
| bool | always_externally_updated_collision_scene_ | 
| bool | needs_update_of_collision_objects_ | 
| bool | replace_cylinders_with_capsules_ | 
| bool | replace_primitive_shapes_with_meshes_ | 
| double | robot_link_padding_ | 
| std::string | robot_link_replacement_config_ | 
| double | robot_link_scale_ | 
| std::weak_ptr< Scene > | scene_ | 
| double | world_link_padding_ | 
| double | world_link_scale_ | 
|  Protected Attributes inherited from exotica::Instantiable< CollisionSceneFCLLatestInitializer > | |
| CollisionSceneFCLLatestInitializer | parameters_ | 
Definition at line 44 of file collision_scene_fcl_latest.h.
| 
 | staticprivate | 
Definition at line 320 of file collision_scene_fcl_latest.cpp.
| 
 | static | 
Definition at line 337 of file collision_scene_fcl_latest.cpp.
| 
 | static | 
Definition at line 529 of file collision_scene_fcl_latest.cpp.
| 
 | staticprivate | 
Definition at line 347 of file collision_scene_fcl_latest.cpp.
| 
 | private | 
Definition at line 160 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Performs a continuous collision check between two objects with a linear interpolation between two given.
| [in] | o1 | The first collision object, by name. | 
| [in] | tf1_beg | The beginning transform for o1. | 
| [in] | tf1_end | The end transform for o1. | 
| [in] | o2 | The second collision object, by name. | 
| [in] | tf2_beg | The beginning transform for o2. | 
| [in] | tf2_end | The end transform for o2. | 
Reimplemented from exotica::CollisionScene.
Definition at line 764 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Computes collision distances.
| self | Indicate if self collision check is required. | 
Reimplemented from exotica::CollisionScene.
Definition at line 579 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 589 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 617 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 677 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 622 of file collision_scene_fcl_latest.cpp.
| 
 | inlineprivate | 
Definition at line 162 of file collision_scene_fcl_latest.h.
| 
 | overridevirtual | 
Gets the collision robot links.
Implements exotica::CollisionScene.
Definition at line 759 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Gets the collision world links.
Implements exotica::CollisionScene.
Definition at line 754 of file collision_scene_fcl_latest.cpp.
| 
 | inlineprivate | 
Definition at line 138 of file collision_scene_fcl_latest.h.
| 
 | inlineprivate | 
Definition at line 146 of file collision_scene_fcl_latest.h.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 688 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 718 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Implements exotica::CollisionScene.
Definition at line 748 of file collision_scene_fcl_latest.cpp.
| 
 | inlineprivate | 
Definition at line 154 of file collision_scene_fcl_latest.h.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 270 of file collision_scene_fcl_latest.cpp.
| 
 | static | 
Definition at line 295 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 549 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Check if the whole robot is valid (collision only).
| self | Indicate if self collision check is required. | 
Implements exotica::CollisionScene.
Definition at line 538 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Reimplemented from exotica::CollisionScene.
Definition at line 66 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Creates the collision scene from kinematic elements.
| objects | Vector kinematic element pointers of collision objects. | 
Implements exotica::CollisionScene.
Definition at line 73 of file collision_scene_fcl_latest.cpp.
| 
 | overridevirtual | 
Updates collision object transformations from the kinematic tree.
Implements exotica::CollisionScene.
Definition at line 132 of file collision_scene_fcl_latest.cpp.
| 
 | private | 
Definition at line 122 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 129 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 128 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 134 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 135 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 136 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 130 of file collision_scene_fcl_latest.h.
| 
 | private | 
Definition at line 131 of file collision_scene_fcl_latest.h.