Tesseract
Motion Planning Environment
Loading...
Searching...
No Matches
Namespaces | Classes | Typedefs | Enumerations | Functions | Variables
tesseract_collision Namespace Reference

Namespaces

namespace  FLOAT_MATH
 
namespace  RAYCAST_MESH
 
namespace  tesseract_collision_bullet
 
namespace  tesseract_collision_fcl
 
namespace  test_suite
 
namespace  VHACD
 

Classes

struct  CollisionCheckConfig
 This is a high level structure containing common information that collision checking utilities need. The goal of this config is to allow all collision checking utilities and planners to use the same data structure. More...
 
struct  ContactManagerConfig
 Contains parameters used to configure a contact manager before a series of contact checks. More...
 
class  ContactManagersPluginFactory
 
struct  ContactRequest
 The ContactRequest struct. More...
 
struct  ContactResult
 
class  ContactResultMap
 This structure hold contact results for link pairs. More...
 
struct  ContactTestData
 This data is intended only to be used internal to the collision checkers as a container and should not be externally used by other libraries or packages. More...
 
class  ContinuousContactManager
 
class  ContinuousContactManagerFactory
 Define a continuous contact manager plugin which the factory can create an instance. More...
 
class  ConvexDecomposition
 
class  ConvexDecompositionHACD
 
class  ConvexDecompositionVHACD
 
class  DiscreteContactManager
 
class  DiscreteContactManagerFactory
 Define a discrete contact manager plugin which the factory can create an instance. More...
 
struct  HACDParameters
 
class  ProgressCallback
 
struct  VHACDParameters
 

Typedefs

using ObjectPairKey = std::pair< std::string, std::string >
 
using CollisionShapesConst = std::vector< tesseract_geometry::Geometry::ConstPtr >
 
using CollisionShapeConstPtr = tesseract_geometry::Geometry::ConstPtr
 
using CollisionShapePtr = tesseract_geometry::Geometry::Ptr
 
using CollisionMarginData = tesseract_common::CollisionMarginData
 
using CollisionMarginOverrideType = tesseract_common::CollisionMarginOverrideType
 
using PairsCollisionMarginData = tesseract_common::PairsCollisionMarginData
 
using IsContactAllowedFn = std::function< bool(const std::string &, const std::string &)>
 Should return true if contact allowed, otherwise false. More...
 
using ContactResultVector = tesseract_common::AlignedVector< ContactResult >
 
using IsContactResultValidFn = std::function< bool(const ContactResult &)>
 Should return true if contact results are valid, otherwise false. More...
 

Enumerations

enum class  ContinuousCollisionType { CCType_None , CCType_Time0 , CCType_Time1 , CCType_Between }
 
enum class  ContactTestType { FIRST = 0 , CLOSEST = 1 , ALL = 2 , LIMITED = 3 }
 
enum class  CollisionEvaluatorType {
  NONE , DISCRETE , LVS_DISCRETE , CONTINUOUS ,
  LVS_CONTINUOUS
}
 High level descriptor used in planners and utilities to specify what kind of collision check is desired. More...
 
enum class  ACMOverrideType { NONE , ASSIGN , AND , OR }
 Identifies how the provided AllowedCollisionMatrix should be applied relative to the isAllowedFn in the contact manager. More...
 

Functions

int createConvexHull (tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, const tesseract_common::VectorVector3d &input, double shrink=-1, double shrinkClamp=-1)
 Create a convex hull from vertices using Bullet Convex Hull Computer. More...
 
tesseract_geometry::ConvexMesh::Ptr makeConvexMesh (const tesseract_geometry::Mesh &mesh)
 
std::vector< ObjectPairKeygetCollisionObjectPairs (const std::vector< std::string > &active_links, const std::vector< std::string > &static_links, const IsContactAllowedFn &acm=nullptr)
 Get a vector of possible collision object pairs. More...
 
bool isLinkActive (const std::vector< std::string > &active, const std::string &name)
 This will check if a link is active provided a list. If the list is empty the link is considered active. More...
 
bool isContactAllowed (const std::string &name1, const std::string &name2, const IsContactAllowedFn &acm, bool verbose=false)
 Determine if contact is allowed between two objects. More...
 
ContactResultprocessResult (ContactTestData &cdata, ContactResult &contact, const std::pair< std::string, std::string > &key, bool found)
 processResult Processes the ContactResult based on the information in the ContactTestData More...
 
void scaleVertices (tesseract_common::VectorVector3d &vertices, const Eigen::Vector3d &center, const Eigen::Vector3d &scale)
 Apply scaling to the geometry coordinates. More...
 
void scaleVertices (tesseract_common::VectorVector3d &vertices, const Eigen::Vector3d &scale)
 Apply scaling to the geometry coordinates. More...
 
bool writeSimplePlyFile (const std::string &path, const tesseract_common::VectorVector3d &vertices, const std::vector< Eigen::Vector3i > &vectices_color, const Eigen::VectorXi &faces, int num_faces)
 Write a simple ply file given vertices and faces. More...
 
bool writeSimplePlyFile (const std::string &path, const tesseract_common::VectorVector3d &vertices, const Eigen::VectorXi &faces, int num_faces)
 Write a simple ply file given vertices and faces. More...
 
int loadSimplePlyFile (const std::string &path, tesseract_common::VectorVector3d &vertices, Eigen::VectorXi &faces, bool triangles_only=false)
 Loads a simple ply file given a path. More...
 
IsContactAllowedFn combineContactAllowedFn (const IsContactAllowedFn &original, const IsContactAllowedFn &override, ACMOverrideType type=ACMOverrideType::OR)
 Combines two IsContactAllowedFns using the override type. More...
 
template<typename ManagerType >
void applyIsContactAllowedFnOverride (ManagerType &manager, const tesseract_common::AllowedCollisionMatrix &acm, ACMOverrideType type)
 Applies ACM to contact manager using override type. More...
 
template<typename ManagerType >
void applyModifyObjectEnabled (ManagerType &manager, const std::unordered_map< std::string, bool > &modify_object_enabled)
 Loops over the map and for every object string either enables or disables it based on the value (true=enable, false=disable) More...
 

Variables

static const std::vector< std::string > ContactTestTypeStrings
 

Typedef Documentation

◆ CollisionMarginData

◆ CollisionMarginOverrideType

◆ CollisionShapeConstPtr

◆ CollisionShapePtr

◆ CollisionShapesConst

◆ ContactResultVector

◆ IsContactAllowedFn

using tesseract_collision::IsContactAllowedFn = typedef std::function<bool(const std::string&, const std::string&)>

Should return true if contact allowed, otherwise false.

Also the order of strings should not matter, the function should handled by the function.

◆ IsContactResultValidFn

using tesseract_collision::IsContactResultValidFn = typedef std::function<bool(const ContactResult&)>

Should return true if contact results are valid, otherwise false.

This is used so users may provide a callback to reject/approve collision results in various algorithms.

◆ ObjectPairKey

using tesseract_collision::ObjectPairKey = typedef std::pair<std::string, std::string>

◆ PairsCollisionMarginData

Enumeration Type Documentation

◆ ACMOverrideType

Identifies how the provided AllowedCollisionMatrix should be applied relative to the isAllowedFn in the contact manager.

Enumerator
NONE 

Do not apply AllowedCollisionMatrix.

ASSIGN 

Replace the current IsContactAllowedFn with one generated from the ACM provided.

AND 

New IsContactAllowedFn combines the contact manager fn and the ACM generated fn with and AND.

OR 

New IsContactAllowedFn combines the contact manager fn and the ACM generated fn with and OR.

◆ CollisionEvaluatorType

High level descriptor used in planners and utilities to specify what kind of collision check is desired.

DISCRETE - Discrete contact manager using only steps specified LVS_DISCRETE - Discrete contact manager interpolating using longest valid segment CONTINUOUS - Continuous contact manager using only steps specified LVS_CONTINUOUS - Continuous contact manager interpolating using longest valid segment

Enumerator
NONE 

None.

DISCRETE 

Discrete contact manager using only steps specified.

LVS_DISCRETE 

Discrete contact manager interpolating using longest valid segment.

CONTINUOUS 

Continuous contact manager using only steps specified.

LVS_CONTINUOUS 

Continuous contact manager interpolating using longest valid segment.

◆ ContactTestType

Enumerator
FIRST 

Return at first contact for any pair of objects

CLOSEST 

Return the global minimum for a pair of objects

ALL 

Return all contacts for a pair of objects

LIMITED 

Return limited set of contacts for a pair of objects

◆ ContinuousCollisionType

Enumerator
CCType_None 
CCType_Time0 
CCType_Time1 
CCType_Between 

Function Documentation

◆ applyIsContactAllowedFnOverride()

template<typename ManagerType >
void tesseract_collision::applyIsContactAllowedFnOverride ( ManagerType &  manager,
const tesseract_common::AllowedCollisionMatrix acm,
ACMOverrideType  type 
)
inline

Applies ACM to contact manager using override type.

Parameters
managerManager whose IsContactAllowedFn will be overwritten
acmACM used to create IsContactAllowedFn
typeDetermines how the two IsContactAllowedFns are combined

◆ applyModifyObjectEnabled()

template<typename ManagerType >
void tesseract_collision::applyModifyObjectEnabled ( ManagerType &  manager,
const std::unordered_map< std::string, bool > &  modify_object_enabled 
)
inline

Loops over the map and for every object string either enables or disables it based on the value (true=enable, false=disable)

Parameters
managerManager that will be modified
modify_object_enabledMap of [key]:value = [object name]:disable or enable

◆ combineContactAllowedFn()

IsContactAllowedFn tesseract_collision::combineContactAllowedFn ( const IsContactAllowedFn original,
const IsContactAllowedFn override,
ACMOverrideType  type = ACMOverrideType::OR 
)

Combines two IsContactAllowedFns using the override type.

Parameters
originalOriginal IsContactAllowedFns. This will be returned if ACMOverrideType is None
overrideOverriding IsContactAllowedFns. This will be returned if ACMOverrideType is ASSIGN
typeOverride type used to combine the IsContactAllowedFns
Returns
One IsContactAllowedFn that combines the two

◆ createConvexHull()

int tesseract_collision::createConvexHull ( tesseract_common::VectorVector3d vertices,
Eigen::VectorXi &  faces,
const tesseract_common::VectorVector3d input,
double  shrink = -1,
double  shrinkClamp = -1 
)

Create a convex hull from vertices using Bullet Convex Hull Computer.

Parameters
(Output)vertices A vector of vertices
(Output)faces The first values indicates the number of vertices that define the face followed by the vertices index
(input)input A vector of point to create a convex hull from
(input)shrink If positive, the convex hull is shrunken by that amount (each face is moved by "shrink" length units towards the center along its normal).
(input)shrinkClamp If positive, "shrink" is clamped to not exceed "shrinkClamp * innerRadius", where "innerRadius" is the minimum distance of a face to the center of the convex hull.
Returns
The number of faces. If less than zero an error occurred when trying to create the convex hull

◆ getCollisionObjectPairs()

std::vector< ObjectPairKey > tesseract_collision::getCollisionObjectPairs ( const std::vector< std::string > &  active_links,
const std::vector< std::string > &  static_links,
const IsContactAllowedFn acm = nullptr 
)

Get a vector of possible collision object pairs.

Todo:
Should this also filter out links without geometry?
Parameters
active_linksThe active link names
static_linksThe static link names
acmThe is contact allowed function
Returns
A vector of collision object pairs

◆ isContactAllowed()

bool tesseract_collision::isContactAllowed ( const std::string &  name1,
const std::string &  name2,
const IsContactAllowedFn acm,
bool  verbose = false 
)

Determine if contact is allowed between two objects.

Parameters
name1The name of the first object
name2The name of the second object
acmThe contact allowed function
verboseIf true print debug information
Returns
True if contact is allowed between the two object, otherwise false.

◆ isLinkActive()

bool tesseract_collision::isLinkActive ( const std::vector< std::string > &  active,
const std::string &  name 
)

This will check if a link is active provided a list. If the list is empty the link is considered active.

Parameters
activeList of active link names
nameThe name of link to check if it is active.

◆ loadSimplePlyFile()

int tesseract_collision::loadSimplePlyFile ( const std::string &  path,
tesseract_common::VectorVector3d vertices,
Eigen::VectorXi &  faces,
bool  triangles_only = false 
)

Loads a simple ply file given a path.

Parameters
pathThe file path
verticesA vector of vertices
facesThe first values indicates the number of vertices that define the face followed by the vertice index
triangles_onlyConvert to only include triangles
Returns
Number of faces, If returned 0 it failed to load.

◆ makeConvexMesh()

tesseract_geometry::ConvexMesh::Ptr tesseract_collision::makeConvexMesh ( const tesseract_geometry::Mesh mesh)

◆ processResult()

ContactResult * tesseract_collision::processResult ( ContactTestData cdata,
ContactResult contact,
const std::pair< std::string, std::string > &  key,
bool  found 
)

processResult Processes the ContactResult based on the information in the ContactTestData

Parameters
cdataInformation used to process the results
contactContacts from the collision checkers that will be processed
keyLink pair used as a key to look up pair specific settings
foundSpecifies whether or not a collision has already been found
Returns
Pointer to the ContactResult.

◆ scaleVertices() [1/2]

void tesseract_collision::scaleVertices ( tesseract_common::VectorVector3d vertices,
const Eigen::Vector3d &  center,
const Eigen::Vector3d &  scale 
)

Apply scaling to the geometry coordinates.

Given a scaling factor s, and center c, a given vertice v is transformed according to s (v - c) + c.

Parameters
verticesThe vertices to scale
centerThe point at which to scale the data about
scaleThe scale factor to apply to the vertices.

◆ scaleVertices() [2/2]

void tesseract_collision::scaleVertices ( tesseract_common::VectorVector3d vertices,
const Eigen::Vector3d &  scale 
)

Apply scaling to the geometry coordinates.

Given a scaling factor s, and center c, a given vertice v is transformed according to s (v - c) + c.

Parameters
verticesThe vertices to scale
scaleThe scale factor to apply to the vertices.

◆ writeSimplePlyFile() [1/2]

bool tesseract_collision::writeSimplePlyFile ( const std::string &  path,
const tesseract_common::VectorVector3d vertices,
const Eigen::VectorXi &  faces,
int  num_faces 
)

Write a simple ply file given vertices and faces.

Parameters
pathThe file path
verticesA vector of vertices
facesThe first values indicates the number of vertices that define the face followed by the vertice index
num_facesThe number of faces
Returns
False if failed to write file, otherwise true

◆ writeSimplePlyFile() [2/2]

bool tesseract_collision::writeSimplePlyFile ( const std::string &  path,
const tesseract_common::VectorVector3d vertices,
const std::vector< Eigen::Vector3i > &  vectices_color,
const Eigen::VectorXi &  faces,
int  num_faces 
)

Write a simple ply file given vertices and faces.

Parameters
pathThe file path
verticesA vector of vertices
vertices_colorThe vertices color (0-255,0-255,0-255), if empty uses a default color
facesThe first values indicates the number of vertices that define the face followed by the vertice index
num_facesThe number of faces
Returns
False if failed to write file, otherwise true

Variable Documentation

◆ ContactTestTypeStrings

const std::vector<std::string> tesseract_collision::ContactTestTypeStrings
static
Initial value:
= {
"FIRST",
"CLOSEST",
"ALL",
"LIMITED",
}