Public Member Functions | Public Attributes | Protected Attributes | List of all members
exotica::CollisionScene Class Referenceabstract

The class of collision scene. More...

#include <collision_scene.h>

Inheritance diagram for exotica::CollisionScene:
Inheritance graph
[legend]

Public Member Functions

void AssignScene (std::shared_ptr< Scene > scene)
 Sets a scene pointer to the CollisionScene for access to methods. More...
 
 CollisionScene ()
 
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...
 
virtual 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)
 Performs a continuous collision check between two objects with a linear interpolation between two given. More...
 
bool get_replace_cylinders_with_capsules () const
 
bool GetAlwaysExternallyUpdatedCollisionScene () const
 
virtual std::vector< CollisionProxyGetCollisionDistance (bool self)
 Computes collision distances. More...
 
virtual std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const std::string &o2)
 Computes collision distances between two objects. More...
 
virtual std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const bool &self)
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1. More...
 
virtual std::vector< CollisionProxyGetCollisionDistance (const std::string &o1, const bool &self, const bool &disable_collision_scene_update)
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to object o1. More...
 
virtual std::vector< CollisionProxyGetCollisionDistance (const std::vector< std::string > &objects, const bool &self)
 Gets the closest distance of any collision object which is allowed to collide with any collision object related to any of the objects. More...
 
virtual std::vector< std::string > GetCollisionRobotLinks ()=0
 Gets the collision robot links. More...
 
virtual std::vector< std::string > GetCollisionWorldLinks ()=0
 Gets the collision world links. More...
 
bool GetReplacePrimitiveShapesWithMeshes () const
 
double GetRobotLinkPadding () const
 
double GetRobotLinkScale () const
 
virtual std::vector< CollisionProxyGetRobotToRobotCollisionDistance (double check_margin)
 Gets the closest distances between links within the robot that are closer than check_margin. More...
 
virtual std::vector< CollisionProxyGetRobotToWorldCollisionDistance (double check_margin)
 Gets the closest distances between links of the robot and the environment that are closer than check_margin. More...
 
virtual Eigen::Vector3d GetTranslation (const std::string &name)=0
 Returns the translation of the named collision object. More...
 
double GetWorldLinkPadding () const
 
double GetWorldLinkScale () const
 
virtual void InstantiateBase (const Initializer &init)
 Instantiates the base properties of the CollisionScene. More...
 
virtual bool IsAllowedToCollide (const std::string &o1, const std::string &o2, const bool &self)
 Returns whether two collision objects/shapes are allowed to collide by name. More...
 
virtual bool IsCollisionFree (const std::string &o1, const std::string &o2, double safe_distance=0.0)
 Checks if two objects are in collision. More...
 
virtual bool IsStateValid (bool self=true, double safe_distance=0.0)=0
 Checks if the whole robot is valid (collision only). More...
 
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)
 
virtual void Setup ()
 Setup additional construction that requires initialiser parameter. More...
 
void SetWorldLinkPadding (const double padding)
 
void SetWorldLinkScale (const double scale)
 
virtual void UpdateCollisionObjects (const std::map< std::string, std::weak_ptr< KinematicElement >> &objects)=0
 Creates the collision scene from kinematic elements. More...
 
virtual void UpdateCollisionObjectTransforms ()=0
 Updates collision object transformations from the kinematic tree. More...
 
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
 Type Information wrapper: must be virtual so that it is polymorphic... More...
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::Uncopyable
 Uncopyable ()=default
 
 ~Uncopyable ()=default
 
- Public Member Functions inherited from exotica::InstantiableBase
virtual std::vector< InitializerGetAllTemplates () const =0
 
virtual Initializer GetInitializerTemplate ()=0
 
 InstantiableBase ()=default
 
virtual void InstantiateInternal (const Initializer &init)=0
 
virtual ~InstantiableBase ()=default
 

Public Attributes

bool debug_ = false
 
- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 

Protected Attributes

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...
 
bool needs_update_of_collision_objects_ = true
 Indicates whether TriggerUpdateCollisionObjects needs to be called. More...
 
bool replace_cylinders_with_capsules_ = false
 Replace cylinders with capsules internally. 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...
 
double robot_link_padding_ = 0.0
 Robot link padding. More...
 
std::string robot_link_replacement_config_ = ""
 Filename for config file (YAML) which contains shape replacements. More...
 
double robot_link_scale_ = 1.0
 Robot link scaling. More...
 
std::weak_ptr< Scenescene_
 Stores a pointer to the Scene which owns this CollisionScene. More...
 
double world_link_padding_ = 0.0
 World link padding. More...
 
double world_link_scale_ = 1.0
 World link scaling. More...
 

Detailed Description

The class of collision scene.

Definition at line 148 of file collision_scene.h.

Constructor & Destructor Documentation

exotica::CollisionScene::CollisionScene ( )
inline

Definition at line 151 of file collision_scene.h.

virtual exotica::CollisionScene::~CollisionScene ( )
inlinevirtual

Definition at line 152 of file collision_scene.h.

Member Function Documentation

void exotica::CollisionScene::AssignScene ( std::shared_ptr< Scene scene)
inline

Sets a scene pointer to the CollisionScene for access to methods.

Definition at line 301 of file collision_scene.h.

virtual std::vector<ContinuousCollisionProxy> exotica::CollisionScene::ContinuousCollisionCast ( const std::vector< std::vector< std::tuple< std::string, Eigen::Isometry3d, Eigen::Isometry3d >>> &  motion_transforms)
inlinevirtual

Performs a continuous collision check by casting the active objects passed in against the static environment.

Parameters
[in]motion_transformsA tuple consisting out of collision object name and its beginning and final transform.
Returns
Vector of deepest ContinuousCollisionProxy (one per dimension).

Definition at line 225 of file collision_scene.h.

virtual ContinuousCollisionProxy exotica::CollisionScene::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 
)
inlinevirtual

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.

Definition at line 221 of file collision_scene.h.

bool exotica::CollisionScene::get_replace_cylinders_with_capsules ( ) const
inline

Definition at line 291 of file collision_scene.h.

bool exotica::CollisionScene::GetAlwaysExternallyUpdatedCollisionScene ( ) const
inline

Definition at line 235 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetCollisionDistance ( bool  self)
inlinevirtual

Computes collision distances.

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

Definition at line 179 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetCollisionDistance ( const std::string &  o1,
const std::string &  o2 
)
inlinevirtual

Computes collision distances between two objects.

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

Definition at line 184 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetCollisionDistance ( const std::string &  o1,
const bool &  self 
)
inlinevirtual

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.

Definition at line 188 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetCollisionDistance ( const std::string &  o1,
const bool &  self,
const bool &  disable_collision_scene_update 
)
inlinevirtual

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.

Definition at line 193 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetCollisionDistance ( const std::vector< std::string > &  objects,
const bool &  self 
)
inlinevirtual

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.

Definition at line 198 of file collision_scene.h.

virtual std::vector<std::string> exotica::CollisionScene::GetCollisionRobotLinks ( )
pure virtual

Gets the collision robot links.

Returns
The collision robot links.
virtual std::vector<std::string> exotica::CollisionScene::GetCollisionWorldLinks ( )
pure virtual

Gets the collision world links.

Returns
The collision world links.
bool exotica::CollisionScene::GetReplacePrimitiveShapesWithMeshes ( ) const
inline

Definition at line 277 of file collision_scene.h.

double exotica::CollisionScene::GetRobotLinkPadding ( ) const
inline

Definition at line 259 of file collision_scene.h.

double exotica::CollisionScene::GetRobotLinkScale ( ) const
inline

Definition at line 241 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetRobotToRobotCollisionDistance ( double  check_margin)
inlinevirtual

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

Definition at line 201 of file collision_scene.h.

virtual std::vector<CollisionProxy> exotica::CollisionScene::GetRobotToWorldCollisionDistance ( double  check_margin)
inlinevirtual

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

Definition at line 204 of file collision_scene.h.

virtual Eigen::Vector3d exotica::CollisionScene::GetTranslation ( const std::string &  name)
pure virtual

Returns the translation of the named collision object.

Parameters
[in]nameName of the collision object to query.
double exotica::CollisionScene::GetWorldLinkPadding ( ) const
inline

Definition at line 268 of file collision_scene.h.

double exotica::CollisionScene::GetWorldLinkScale ( ) const
inline

Definition at line 250 of file collision_scene.h.

void exotica::CollisionScene::InstantiateBase ( const Initializer init)
virtual

Instantiates the base properties of the CollisionScene.

Reimplemented from exotica::InstantiableBase.

Definition at line 42 of file collision_scene.cpp.

bool exotica::CollisionScene::IsAllowedToCollide ( const std::string &  o1,
const std::string &  o2,
const bool &  self 
)
virtual

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.

Definition at line 58 of file collision_scene.cpp.

virtual bool exotica::CollisionScene::IsCollisionFree ( const std::string &  o1,
const std::string &  o2,
double  safe_distance = 0.0 
)
inlinevirtual

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.

Definition at line 174 of file collision_scene.h.

virtual bool exotica::CollisionScene::IsStateValid ( bool  self = true,
double  safe_distance = 0.0 
)
pure virtual

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

Parameters
selfIndicate if self collision check is required.
Returns
True, if the state is collision free..
void exotica::CollisionScene::set_replace_cylinders_with_capsules ( const bool  value)
inline

Definition at line 292 of file collision_scene.h.

void exotica::CollisionScene::SetACM ( const AllowedCollisionMatrix acm)
inline

Definition at line 230 of file collision_scene.h.

void exotica::CollisionScene::SetAlwaysExternallyUpdatedCollisionScene ( const bool  value)
inline

Definition at line 236 of file collision_scene.h.

void exotica::CollisionScene::SetReplacePrimitiveShapesWithMeshes ( const bool  value)
inline

Definition at line 278 of file collision_scene.h.

void exotica::CollisionScene::SetRobotLinkPadding ( const double  padding)
inline

Definition at line 260 of file collision_scene.h.

void exotica::CollisionScene::SetRobotLinkScale ( const double  scale)
inline

Definition at line 242 of file collision_scene.h.

virtual void exotica::CollisionScene::Setup ( )
inlinevirtual

Setup additional construction that requires initialiser parameter.

Definition at line 157 of file collision_scene.h.

void exotica::CollisionScene::SetWorldLinkPadding ( const double  padding)
inline

Definition at line 269 of file collision_scene.h.

void exotica::CollisionScene::SetWorldLinkScale ( const double  scale)
inline

Definition at line 251 of file collision_scene.h.

virtual void exotica::CollisionScene::UpdateCollisionObjects ( const std::map< std::string, std::weak_ptr< KinematicElement >> &  objects)
pure virtual

Creates the collision scene from kinematic elements.

Parameters
objectsVector kinematic element pointers of collision objects.
virtual void exotica::CollisionScene::UpdateCollisionObjectTransforms ( )
pure virtual

Updates collision object transformations from the kinematic tree.

Member Data Documentation

AllowedCollisionMatrix exotica::CollisionScene::acm_
protected

The allowed collision matrix.

Definition at line 314 of file collision_scene.h.

bool exotica::CollisionScene::always_externally_updated_collision_scene_ = false
protected

Whether the collision scene is automatically updated - if not, update on queries.

Definition at line 317 of file collision_scene.h.

bool exotica::CollisionScene::debug_ = false

Definition at line 298 of file collision_scene.h.

bool exotica::CollisionScene::needs_update_of_collision_objects_ = true
protected

Indicates whether TriggerUpdateCollisionObjects needs to be called.

Definition at line 308 of file collision_scene.h.

bool exotica::CollisionScene::replace_cylinders_with_capsules_ = false
protected

Replace cylinders with capsules internally.

Definition at line 335 of file collision_scene.h.

bool exotica::CollisionScene::replace_primitive_shapes_with_meshes_ = false
protected

Replace primitive shapes with meshes internally (e.g. when primitive shape algorithms are brittle, i.e. in FCL)

Definition at line 332 of file collision_scene.h.

double exotica::CollisionScene::robot_link_padding_ = 0.0
protected

Robot link padding.

Definition at line 326 of file collision_scene.h.

std::string exotica::CollisionScene::robot_link_replacement_config_ = ""
protected

Filename for config file (YAML) which contains shape replacements.

Definition at line 338 of file collision_scene.h.

double exotica::CollisionScene::robot_link_scale_ = 1.0
protected

Robot link scaling.

Definition at line 320 of file collision_scene.h.

std::weak_ptr<Scene> exotica::CollisionScene::scene_
protected

Stores a pointer to the Scene which owns this CollisionScene.

Definition at line 311 of file collision_scene.h.

double exotica::CollisionScene::world_link_padding_ = 0.0
protected

World link padding.

Definition at line 329 of file collision_scene.h.

double exotica::CollisionScene::world_link_scale_ = 1.0
protected

World link scaling.

Definition at line 323 of file collision_scene.h.


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


exotica_core
Author(s): Yiming Yang, Michael Camilleri
autogenerated on Sat Apr 10 2021 02:34:50