Exotica
Classes | Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Private Attributes | List of all members
exotica::CollisionSceneFCLLatest Class Reference

#include <collision_scene_fcl_latest.h>

Inheritance diagram for exotica::CollisionSceneFCLLatest:
Inheritance graph
Collaboration diagram for exotica::CollisionSceneFCLLatest:
Collaboration graph

Classes

struct  CollisionData
 
struct  DistanceData
 

Public Member Functions

void Setup () override
 Setup additional construction that requires initialiser parameter. More...
 
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. More...
 
bool IsStateValid (bool self=true, double safe_distance=0.0) override
 Check if the whole robot is valid (collision only). More...
 
bool IsCollisionFree (const std::string &o1, const std::string &o2, double safe_distance=0.0) override
 Checks if two objects are in collision. More...
 
std::vector< CollisionProxyGetCollisionDistance (bool self) override
 Computes collision distances. More...
 
std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const std::string &o2) override
 Computes collision distances between two objects. More...
 
std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const bool &self=true) override
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1. More...
 
std::vector< CollisionProxyGetCollisionDistance (const std::vector< std::string > &objects, const bool &self=true) override
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to any of the objects. More...
 
std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const bool &self=true, const bool &disable_collision_scene_update=false) override
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1. More...
 
std::vector< CollisionProxyGetRobotToRobotCollisionDistance (double check_margin) override
 Gets the closest distances between links within the robot that are closer than check_margin. More...
 
std::vector< CollisionProxyGetRobotToWorldCollisionDistance (double check_margin) override
 Gets the closest distances between links of the robot and the environment that are closer than check_margin. More...
 
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< std::string > GetCollisionWorldLinks () override
 Gets the collision world links. More...
 
std::vector< std::string > GetCollisionRobotLinks () override
 Gets the collision robot links. More...
 
Eigen::Vector3d GetTranslation (const std::string &name) override
 Returns the translation of the named collision object. More...
 
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
 CollisionScene ()
 
virtual ~CollisionScene ()
 
virtual void InstantiateBase (const Initializer &init)
 Instantiates the base properties of the CollisionScene. More...
 
virtual std::vector< ContinuousCollisionProxyContinuousCollisionCast (const std::vector< std::vector< std::tuple< std::string, Eigen::Isometry3d, Eigen::Isometry3d >>> &motion_transforms)
 Performs a continuous collision check by casting the active objects passed in against the static environment. More...
 
void SetACM (const AllowedCollisionMatrix &acm)
 
bool GetAlwaysExternallyUpdatedCollisionScene () const
 
void SetAlwaysExternallyUpdatedCollisionScene (const bool value)
 
double GetRobotLinkScale () const
 
void SetRobotLinkScale (const double scale)
 
double GetWorldLinkScale () const
 
void SetWorldLinkScale (const double scale)
 
double GetRobotLinkPadding () const
 
void SetRobotLinkPadding (const double padding)
 
double GetWorldLinkPadding () const
 
void SetWorldLinkPadding (const double padding)
 
bool GetReplacePrimitiveShapesWithMeshes () const
 
void SetReplacePrimitiveShapesWithMeshes (const bool value)
 
bool get_replace_cylinders_with_capsules () const
 
void set_replace_cylinders_with_capsules (const bool value)
 
void AssignScene (std::shared_ptr< Scene > scene)
 Sets a scene pointer to the CollisionScene for access to methods. More...
 
- Public Member Functions inherited from exotica::Object
 Object ()
 
virtual ~Object ()
 
virtual std::string type () const
 Type Information wrapper: must be virtual so that it is polymorphic... More...
 
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
virtual std::string Print (const std::string &prepend) const
 
- Public Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
virtual std::vector< InitializerGetAllTemplates () const =0
 
- Public Member Functions inherited from exotica::Instantiable< CollisionSceneFCLLatestInitializer >
void InstantiateInternal (const Initializer &init) override
 
Initializer GetInitializerTemplate () override
 
std::vector< InitializerGetAllTemplates () const override
 
virtual void Instantiate (const CollisionSceneFCLLatestInitializer &init)
 
const CollisionSceneFCLLatestInitializer & GetParameters () const
 

Static Public Member Functions

static bool IsAllowedToCollide (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, bool self, CollisionSceneFCLLatest *scene)
 
static bool CollisionCallback (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data)
 
static bool CollisionCallbackDistance (fcl::CollisionObjectd *o1, fcl::CollisionObjectd *o2, void *data, double &dist)
 

Private Member Functions

std::shared_ptr< fcl::CollisionObjectd > ConstructFclCollisionObject (long i, std::shared_ptr< KinematicElement > element)
 
std::shared_ptr< KinematicElementGetKinematicElementFromMapByName (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)
 
std::vector< fcl::CollisionObjectd * > GetCollisionObjectsFromMapByName (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< fcl::CollisionObjectd * > fcl_objects_
 
std::vector< std::shared_ptr< fcl::CollisionObjectd > > fcl_cache_
 
std::vector< std::weak_ptr< KinematicElement > > kinematic_elements_
 
std::map< std::string, std::weak_ptr< KinematicElement > > kinematic_elements_map_
 
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_
 

Additional Inherited Members

- Public Attributes inherited from exotica::CollisionScene
bool debug_ = false
 
- Public Attributes inherited from exotica::Object
std::string ns_
 
std::string object_name_
 
bool debug_
 
- Protected Attributes inherited from exotica::CollisionScene
bool needs_update_of_collision_objects_ = true
 Indicates whether TriggerUpdateCollisionObjects needs to be called. More...
 
std::weak_ptr< Scenescene_
 Stores a pointer to the Scene which owns this CollisionScene. More...
 
AllowedCollisionMatrix acm_
 The allowed collision matrix. More...
 
bool always_externally_updated_collision_scene_ = false
 Whether the collision scene is automatically updated - if not, update on queries. More...
 
double robot_link_scale_ = 1.0
 Robot link scaling. More...
 
double world_link_scale_ = 1.0
 World link scaling. More...
 
double robot_link_padding_ = 0.0
 Robot link padding. More...
 
double world_link_padding_ = 0.0
 World link padding. More...
 
bool replace_primitive_shapes_with_meshes_ = false
 Replace primitive shapes with meshes internally (e.g. when primitive shape algorithms are brittle, i.e. in FCL) More...
 
bool replace_cylinders_with_capsules_ = false
 Replace cylinders with capsules internally. More...
 
std::string robot_link_replacement_config_ = ""
 Filename for config file (YAML) which contains shape replacements. More...
 
- Protected Attributes inherited from exotica::Instantiable< CollisionSceneFCLLatestInitializer >
CollisionSceneFCLLatestInitializer parameters_
 

Member Function Documentation

◆ CheckCollision()

static void exotica::CollisionSceneFCLLatest::CheckCollision ( fcl::CollisionObjectd *  o1,
fcl::CollisionObjectd *  o2,
CollisionData data 
)
staticprivate

◆ CollisionCallback()

static bool exotica::CollisionSceneFCLLatest::CollisionCallback ( fcl::CollisionObjectd *  o1,
fcl::CollisionObjectd *  o2,
void *  data 
)
static

◆ CollisionCallbackDistance()

static bool exotica::CollisionSceneFCLLatest::CollisionCallbackDistance ( fcl::CollisionObjectd *  o1,
fcl::CollisionObjectd *  o2,
void *  data,
double &  dist 
)
static

◆ ComputeDistance()

static void exotica::CollisionSceneFCLLatest::ComputeDistance ( fcl::CollisionObjectd *  o1,
fcl::CollisionObjectd *  o2,
DistanceData data 
)
staticprivate

◆ ConstructFclCollisionObject()

std::shared_ptr<fcl::CollisionObjectd> exotica::CollisionSceneFCLLatest::ConstructFclCollisionObject ( long  i,
std::shared_ptr< KinematicElement element 
)
private

◆ ContinuousCollisionCheck()

ContinuousCollisionProxy exotica::CollisionSceneFCLLatest::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 
)
overridevirtual

Performs a continuous collision check between two objects with a linear interpolation between two given.

Parameters
[in]o1The first collision object, by name.
[in]tf1_begThe beginning transform for o1.
[in]tf1_endThe end transform for o1.
[in]o2The second collision object, by name.
[in]tf2_begThe beginning transform for o2.
[in]tf2_endThe end transform for o2.
Returns
ContinuousCollisionProxy.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionDistance() [1/5]

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetCollisionDistance ( bool  self)
overridevirtual

Computes collision distances.

Parameters
selfIndicate if self collision check is required.
Returns
Collision proximity objects for all colliding pairs of objects.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionDistance() [2/5]

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetCollisionDistance ( const std::string &  o1,
const bool &  self = true 
)
overridevirtual

Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1.

Parameters
[in]o1Name of object 1.
Returns
Vector of proximity objects.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionDistance() [3/5]

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetCollisionDistance ( const std::string &  o1,
const bool &  self = true,
const bool &  disable_collision_scene_update = false 
)
overridevirtual

Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1.

Parameters
[in]o1Name of object 1.
[in]disable_collision_scene_updateAllows disabling of collision object transforms (requires manual update).
Returns
Vector of proximity objects.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionDistance() [4/5]

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetCollisionDistance ( const std::string &  o1,
const std::string &  o2 
)
overridevirtual

Computes collision distances between two objects.

Parameters
o1Name of object 1.
o2Name of object 2.
Returns
Vector of proximity objects.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionDistance() [5/5]

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetCollisionDistance ( const std::vector< std::string > &  objects,
const bool &  self = true 
)
overridevirtual

Gets the closest distance of any collision object which is allowed to collide with any collision object related to any of the objects.

Parameters
[in]objectsVector of object names.
Returns
Vector of proximity objects.

Reimplemented from exotica::CollisionScene.

◆ GetCollisionObjectsFromMapByName()

std::vector<fcl::CollisionObjectd*> exotica::CollisionSceneFCLLatest::GetCollisionObjectsFromMapByName ( const std::string &  frame_name)
inlineprivate

◆ GetCollisionRobotLinks()

std::vector<std::string> exotica::CollisionSceneFCLLatest::GetCollisionRobotLinks ( )
overridevirtual

Gets the collision robot links.

Returns
The collision robot links.

Implements exotica::CollisionScene.

◆ GetCollisionWorldLinks()

std::vector<std::string> exotica::CollisionSceneFCLLatest::GetCollisionWorldLinks ( )
overridevirtual

Gets the collision world links.

Returns
The collision world links.

Implements exotica::CollisionScene.

◆ GetKinematicElementFromMapByName()

std::shared_ptr<KinematicElement> exotica::CollisionSceneFCLLatest::GetKinematicElementFromMapByName ( const std::string &  frame_name)
inlineprivate

◆ GetRobotCollisionObjectsFromMapByName()

std::vector<fcl::CollisionObjectd*> exotica::CollisionSceneFCLLatest::GetRobotCollisionObjectsFromMapByName ( const std::string &  frame_name)
inlineprivate

◆ GetRobotToRobotCollisionDistance()

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetRobotToRobotCollisionDistance ( double  check_margin)
overridevirtual

Gets the closest distances between links within the robot that are closer than check_margin.

Parameters
[in]check_marginMargin for distance checks - only objects closer than this margin will be checked

Reimplemented from exotica::CollisionScene.

◆ GetRobotToWorldCollisionDistance()

std::vector<CollisionProxy> exotica::CollisionSceneFCLLatest::GetRobotToWorldCollisionDistance ( double  check_margin)
overridevirtual

Gets the closest distances between links of the robot and the environment that are closer than check_margin.

Parameters
[in]check_marginMargin for distance checks - only objects closer than this margin will be checked

Reimplemented from exotica::CollisionScene.

◆ GetTranslation()

Eigen::Vector3d exotica::CollisionSceneFCLLatest::GetTranslation ( const std::string &  name)
overridevirtual

Returns the translation of the named collision object.

Parameters
[in]nameName of the collision object to query.

Implements exotica::CollisionScene.

◆ GetWorldCollisionObjectsFromMapByName()

std::vector<fcl::CollisionObjectd*> exotica::CollisionSceneFCLLatest::GetWorldCollisionObjectsFromMapByName ( const std::string &  frame_name)
inlineprivate

◆ IsAllowedToCollide() [1/2]

bool exotica::CollisionSceneFCLLatest::IsAllowedToCollide ( const std::string &  o1,
const std::string &  o2,
const bool &  self 
)
overridevirtual

Returns whether two collision objects/shapes are allowed to collide by name.

Parameters
o1Name of the frame of the collision object (e.g., base_link_collision_0)
o2Name of the frame of the other collision object (e.g., base_link_collision_0)
Returns
true The two objects are allowed to collide.
false The two objects are excluded, e.g., by an ACM.

Reimplemented from exotica::CollisionScene.

◆ IsAllowedToCollide() [2/2]

static bool exotica::CollisionSceneFCLLatest::IsAllowedToCollide ( fcl::CollisionObjectd *  o1,
fcl::CollisionObjectd *  o2,
bool  self,
CollisionSceneFCLLatest scene 
)
static

◆ IsCollisionFree()

bool exotica::CollisionSceneFCLLatest::IsCollisionFree ( const std::string &  o1,
const std::string &  o2,
double  safe_distance = 0.0 
)
overridevirtual

Checks if two objects are in collision.

Parameters
o1Name of object 1.
o2Name of object 2.
Returns
True is the two objects are not colliding.

Reimplemented from exotica::CollisionScene.

◆ IsStateValid()

bool exotica::CollisionSceneFCLLatest::IsStateValid ( bool  self = true,
double  safe_distance = 0.0 
)
overridevirtual

Check if the whole robot is valid (collision only).

Parameters
selfIndicate if self collision check is required.
Returns
True, if the state is collision free.

Implements exotica::CollisionScene.

◆ Setup()

void exotica::CollisionSceneFCLLatest::Setup ( )
overridevirtual

Setup additional construction that requires initialiser parameter.

Reimplemented from exotica::CollisionScene.

◆ UpdateCollisionObjects()

void exotica::CollisionSceneFCLLatest::UpdateCollisionObjects ( const std::map< std::string, std::weak_ptr< KinematicElement >> &  objects)
overridevirtual

Creates the collision scene from kinematic elements.

Parameters
objectsVector kinematic element pointers of collision objects.

Implements exotica::CollisionScene.

◆ UpdateCollisionObjectTransforms()

void exotica::CollisionSceneFCLLatest::UpdateCollisionObjectTransforms ( )
overridevirtual

Updates collision object transformations from the kinematic tree.

Implements exotica::CollisionScene.

Member Data Documentation

◆ broad_phase_collision_manager_

std::shared_ptr<fcl::BroadPhaseCollisionManagerd> exotica::CollisionSceneFCLLatest::broad_phase_collision_manager_
private

◆ fcl_cache_

std::vector<std::shared_ptr<fcl::CollisionObjectd> > exotica::CollisionSceneFCLLatest::fcl_cache_
private

◆ fcl_objects_

std::vector<fcl::CollisionObjectd*> exotica::CollisionSceneFCLLatest::fcl_objects_
private

◆ fcl_objects_map_

std::map<std::string, std::vector<fcl::CollisionObjectd*> > exotica::CollisionSceneFCLLatest::fcl_objects_map_
private

◆ fcl_robot_objects_map_

std::map<std::string, std::vector<fcl::CollisionObjectd*> > exotica::CollisionSceneFCLLatest::fcl_robot_objects_map_
private

◆ fcl_world_objects_map_

std::map<std::string, std::vector<fcl::CollisionObjectd*> > exotica::CollisionSceneFCLLatest::fcl_world_objects_map_
private

◆ kinematic_elements_

std::vector<std::weak_ptr<KinematicElement> > exotica::CollisionSceneFCLLatest::kinematic_elements_
private

◆ kinematic_elements_map_

std::map<std::string, std::weak_ptr<KinematicElement> > exotica::CollisionSceneFCLLatest::kinematic_elements_map_
private

The documentation for this class was generated from the following file: