se3::CollisionPair Struct Reference

#include <multibody/geometry.hpp>

List of all members.

Public Types

typedef Model::Index Index
typedef Model::GeomIndex GeomIndex
typedef std::pair
< Model::GeomIndex,
Model::GeomIndex
Base

Public Member Functions

 CollisionPair (const GeomIndex co1, const GeomIndex co2)
 Default constructor of a collision pair from two collision object indexes.
void disp (std::ostream &os) const

Friends

std::ostream & operator<< (std::ostream &os, const CollisionPair &X)

Member Typedef Documentation


Constructor & Destructor Documentation

se3::CollisionPair::CollisionPair ( const GeomIndex  co1,
const GeomIndex  co2 
) [inline]

Default constructor of a collision pair from two collision object indexes.

The indexes must be ordered such that co1 < co2. If not, the constructor reverts the indexes.

Parameters:
[in]co1Index of the first collision object
[in]co2Index of the second collision object

Member Function Documentation

void se3::CollisionPair::disp ( std::ostream &  os) const [inline]

Friends And Related Function Documentation

std::ostream& operator<< ( std::ostream &  os,
const CollisionPair X 
) [friend]