se3::CollisionResult Struct Reference

Result of collision computation between two CollisionObjects. More...

#include <multibody/geometry.hpp>

List of all members.

Public Types

typedef Model::Index Index
typedef Model::GeomIndex GeomIndex

Public Member Functions

 CollisionResult (fcl::CollisionResult coll_fcl, const GeomIndex co1, const GeomIndex co2)
 Default constrcutor of a CollisionResult.
bool operator== (const CollisionResult &other) const

Public Attributes

fcl::CollisionResult fcl_collision_result
 The FCL result of the collision computation.
GeomIndex object1
 Index of the first collision object.
GeomIndex object2
 Index of the second collision object.

Detailed Description

Result of collision computation between two CollisionObjects.


Member Typedef Documentation


Constructor & Destructor Documentation

se3::CollisionResult::CollisionResult ( fcl::CollisionResult  coll_fcl,
const GeomIndex  co1,
const GeomIndex  co2 
) [inline]

Default constrcutor of a CollisionResult.

Parameters:
[in]coll_fclThe FCL collision result
[in]co1Index of the first geometry object involved in the computation
[in]co2Index of the second geometry object involved in the computation

Member Function Documentation

bool se3::CollisionResult::operator== ( const CollisionResult other) const [inline]

Member Data Documentation

The FCL result of the collision computation.

Referenced by operator==().

Index of the first collision object.

Referenced by operator==().

Index of the second collision object.

Referenced by operator==().