Namespaces | |
tesseract_collision_bullet | |
tesseract_collision_fcl | |
test_suite | |
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... | |
class | ContactResultValidator |
Should return true if contact results are valid, otherwise false. 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... | |
struct | ContactTrajectoryResults |
The ContactTrajectoryResults struct is the top level struct for tracking contacts in a trajectory. This struct stores all the steps and therefore all the contacts in a trajectory. It also exposes a method for returning a contact summary table as a string for printing to a terminal. More... | |
struct | ContactTrajectoryStepResults |
The ContactTrajectoryStepResults struct is the second level struct for tracking contacts in a trajectory. This struct stores all the substep contact information as well as the start and end state of the given step in the trajectory. More... | |
struct | ContactTrajectorySubstepResults |
The ContactTrajectorySubstepResults struct is the lowest level struct for tracking contacts in a trajectory. This struct is used for substeps between waypoints in a trajectory when a longest valid segment is used, storing the relevant states of the substep. 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 | CollisionMarginData = tesseract_common::CollisionMarginData |
using | CollisionMarginPairData = tesseract_common::CollisionMarginPairData |
using | CollisionMarginPairOverrideType = tesseract_common::CollisionMarginPairOverrideType |
using | CollisionShapeConstPtr = std::shared_ptr< const tesseract_geometry::Geometry > |
using | CollisionShapePtr = std::shared_ptr< tesseract_geometry::Geometry > |
using | CollisionShapesConst = std::vector< CollisionShapeConstPtr > |
using | ContactResultAnyPoly = tesseract_common::AnyWrapper< ContactResult > |
using | ContactResultMapAnyPoly = tesseract_common::AnyWrapper< ContactResultMap > |
using | ContactResultMapVectorAnyPoly = tesseract_common::AnyWrapper< std::vector< tesseract_collision::ContactResultMap > > |
using | ContactResultVector = tesseract_common::AlignedVector< ContactResult > |
using | ObjectPairKey = std::pair< std::string, std::string > |
Functions | |
template<typename ManagerType > | |
void | applyContactAllowedValidatorOverride (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... | |
tesseract_common::ContactAllowedValidator::ConstPtr | combineContactAllowedValidators (tesseract_common::ContactAllowedValidator::ConstPtr original, tesseract_common::ContactAllowedValidator::ConstPtr override, ACMOverrideType type=ACMOverrideType::OR) |
Combines two ContactAllowedValidator using the override type. More... | |
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... | |
std::vector< ObjectPairKey > | getCollisionObjectPairs (const std::vector< std::string > &active_links, const std::vector< std::string > &static_links, const std::shared_ptr< const tesseract_common::ContactAllowedValidator > &validator=nullptr) |
Get a vector of possible collision object pairs. More... | |
bool | isContactAllowed (const std::string &name1, const std::string &name2, const std::shared_ptr< const tesseract_common::ContactAllowedValidator > &validator, bool verbose=false) |
Determine if contact is allowed between two objects. 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... | |
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... | |
tesseract_geometry::ConvexMesh::Ptr | makeConvexMesh (const tesseract_geometry::Mesh &mesh) |
ContactResult * | 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 More... | |
void | scaleVertices (tesseract_common::VectorVector3d &vertices, const Eigen::Vector3d ¢er, 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 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 std::vector< Eigen::Vector3i > &vectices_color, const Eigen::VectorXi &faces, int num_faces) |
Write a simple ply file given vertices and faces. More... | |
Variables | |
static const std::vector< std::string > | ContactTestTypeStrings |
using tesseract_collision::CollisionShapeConstPtr = typedef std::shared_ptr<const tesseract_geometry::Geometry> |
using tesseract_collision::CollisionShapePtr = typedef std::shared_ptr<tesseract_geometry::Geometry> |
using tesseract_collision::CollisionShapesConst = typedef std::vector<CollisionShapeConstPtr> |
using tesseract_collision::ContactResultMapVectorAnyPoly = typedef tesseract_common::AnyWrapper<std::vector<tesseract_collision::ContactResultMap> > |
using tesseract_collision::ObjectPairKey = typedef std::pair<std::string, std::string> |
|
strong |
Identifies how the provided AllowedCollisionMatrix should be applied relative to the isAllowedFn in the contact manager.
|
strong |
The mode used to check program.
|
strong |
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
|
strong |
|
strong |
|
inline |
|
inline |
tesseract_common::ContactAllowedValidator::ConstPtr tesseract_collision::combineContactAllowedValidators | ( | tesseract_common::ContactAllowedValidator::ConstPtr | original, |
tesseract_common::ContactAllowedValidator::ConstPtr | override, | ||
ACMOverrideType | type = ACMOverrideType::OR |
||
) |
Combines two ContactAllowedValidator using the override type.
original | Original ContactAllowedValidator. This will be returned if ACMOverrideType is None |
override | Overriding ContactAllowedValidator. This will be returned if ACMOverrideType is ASSIGN |
type | Override type used to combine the ContactAllowedValidator |
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.
(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. |
Definition at line 37 of file convex_hull_utils.cpp.
std::vector< ObjectPairKey > tesseract_collision::getCollisionObjectPairs | ( | const std::vector< std::string > & | active_links, |
const std::vector< std::string > & | static_links, | ||
const std::shared_ptr< const tesseract_common::ContactAllowedValidator > & | validator = nullptr |
||
) |
Get a vector of possible collision object pairs.
active_links | The active link names |
static_links | The static link names |
validator | The is contact allowed validator |
Definition at line 45 of file common.cpp.
bool tesseract_collision::isContactAllowed | ( | const std::string & | name1, |
const std::string & | name2, | ||
const std::shared_ptr< const tesseract_common::ContactAllowedValidator > & | validator, | ||
bool | verbose = false |
||
) |
Determine if contact is allowed between two objects.
name1 | The name of the first object |
name2 | The name of the second object |
validator | The contact allowed validator |
verbose | If true print debug information |
Definition at line 85 of file common.cpp.
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.
active | List of active link names |
name | The name of link to check if it is active. |
Definition at line 80 of file common.cpp.
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.
path | The file path |
vertices | A vector of vertices |
faces | The first values indicates the number of vertices that define the face followed by the vertice index |
triangles_only | Convert to only include triangles |
Definition at line 289 of file common.cpp.
tesseract_geometry::ConvexMesh::Ptr tesseract_collision::makeConvexMesh | ( | const tesseract_geometry::Mesh & | mesh | ) |
Definition at line 113 of file convex_hull_utils.cpp.
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
cdata | Information used to process the results |
contact | Contacts from the collision checkers that will be processed |
key | Link pair used as a key to look up pair specific settings |
found | Specifies whether or not a collision has already been found |
Definition at line 112 of file common.cpp.
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.
vertices | The vertices to scale |
center | The point at which to scale the data about |
scale | The scale factor to apply to the vertices. |
Definition at line 155 of file common.cpp.
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.
vertices | The vertices to scale |
scale | The scale factor to apply to the vertices. |
Definition at line 163 of file common.cpp.
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.
path | The file path |
vertices | A vector of vertices |
faces | The first values indicates the number of vertices that define the face followed by the vertice index |
num_faces | The number of faces |
Definition at line 280 of file common.cpp.
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.
path | The file path |
vertices | A vector of vertices |
vertices_color | The vertices color (0-255,0-255,0-255), if empty uses a default color |
faces | The first values indicates the number of vertices that define the face followed by the vertice index |
num_faces | The number of faces |
Definition at line 174 of file common.cpp.