Public Member Functions | Public Attributes | List of all members
tesseract_collision::ContactResult Struct Reference

#include <types.h>

Public Member Functions

void clear ()
 reset to default values More...
 
 ContactResult ()=default
 
bool operator!= (const ContactResult &rhs) const
 
bool operator== (const ContactResult &rhs) const
 

Public Attributes

std::array< double, 2 > cc_time { -1, -1 }
 This is between 0 and 1 indicating the point of contact. More...
 
std::array< Eigen::Isometry3d, 2 > cc_transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() }
 The transform of link in world coordinates at its desired final location. Note: This is not the location of the link at the point of contact but the final location the link when performing continuous collision checking. If you desire the location of contact use cc_time and interpolate between transform and cc_transform;. More...
 
std::array< ContinuousCollisionType, 2 > cc_type
 The type of continuous contact. More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double distance { std::numeric_limits<double>::max() }
 The distance between two links. More...
 
std::array< std::string, 2 > link_names
 The two links that are in contact. More...
 
std::array< Eigen::Vector3d, 2 > nearest_points { Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero() }
 The nearest point on both links in world coordinates. More...
 
std::array< Eigen::Vector3d, 2 > nearest_points_local { Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero() }
 The nearest point on both links in local(link) coordinates. More...
 
Eigen::Vector3d normal { Eigen::Vector3d::Zero() }
 The normal vector to move the two objects out of contact in world coordinates. More...
 
std::array< int, 2 > shape_id { -1, -1 }
 The two shapes that are in contact. Each link can be made up of multiple shapes. More...
 
bool single_contact_point { false }
 Some collision checkers only provide a single contact point for a given pair. This is used to indicate if only one contact point is provided which means nearest_points[0] must equal nearest_points[1]. More...
 
std::array< int, 2 > subshape_id { -1, -1 }
 Some shapes like octomap and mesh have subshape (boxes and triangles) More...
 
std::array< Eigen::Isometry3d, 2 > transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() }
 The transform of link in world coordinates. More...
 
std::array< int, 2 > type_id { 0, 0 }
 A user defined type id that is added to the contact shapes. More...
 

Detailed Description

Definition at line 81 of file types.h.

Constructor & Destructor Documentation

◆ ContactResult()

tesseract_collision::ContactResult::ContactResult ( )
default

Member Function Documentation

◆ clear()

void tesseract_collision::ContactResult::clear ( )

reset to default values

Definition at line 36 of file types.cpp.

◆ operator!=()

bool tesseract_collision::ContactResult::operator!= ( const ContactResult rhs) const

Definition at line 87 of file types.cpp.

◆ operator==()

bool tesseract_collision::ContactResult::operator== ( const ContactResult rhs) const

Definition at line 63 of file types.cpp.

Member Data Documentation

◆ cc_time

std::array<double, 2> tesseract_collision::ContactResult::cc_time { -1, -1 }

This is between 0 and 1 indicating the point of contact.

Definition at line 111 of file types.h.

◆ cc_transform

std::array<Eigen::Isometry3d, 2> tesseract_collision::ContactResult::cc_transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() }

The transform of link in world coordinates at its desired final location. Note: This is not the location of the link at the point of contact but the final location the link when performing continuous collision checking. If you desire the location of contact use cc_time and interpolate between transform and cc_transform;.

Definition at line 120 of file types.h.

◆ cc_type

std::array<ContinuousCollisionType, 2> tesseract_collision::ContactResult::cc_type
Initial value:

The type of continuous contact.

Definition at line 113 of file types.h.

◆ distance

EIGEN_MAKE_ALIGNED_OPERATOR_NEW double tesseract_collision::ContactResult::distance { std::numeric_limits<double>::max() }

The distance between two links.

Definition at line 88 of file types.h.

◆ link_names

std::array<std::string, 2> tesseract_collision::ContactResult::link_names

The two links that are in contact.

Definition at line 92 of file types.h.

◆ nearest_points

std::array<Eigen::Vector3d, 2> tesseract_collision::ContactResult::nearest_points { Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero() }

The nearest point on both links in world coordinates.

Definition at line 98 of file types.h.

◆ nearest_points_local

std::array<Eigen::Vector3d, 2> tesseract_collision::ContactResult::nearest_points_local { Eigen::Vector3d::Zero(), Eigen::Vector3d::Zero() }

The nearest point on both links in local(link) coordinates.

Definition at line 100 of file types.h.

◆ normal

Eigen::Vector3d tesseract_collision::ContactResult::normal { Eigen::Vector3d::Zero() }

The normal vector to move the two objects out of contact in world coordinates.

Note
This points from link_name[0] to link_name[1], so it shows the direction to move link_name[1] to avoid or get out of collision with link_name[0].

Definition at line 109 of file types.h.

◆ shape_id

std::array<int, 2> tesseract_collision::ContactResult::shape_id { -1, -1 }

The two shapes that are in contact. Each link can be made up of multiple shapes.

Definition at line 94 of file types.h.

◆ single_contact_point

bool tesseract_collision::ContactResult::single_contact_point { false }

Some collision checkers only provide a single contact point for a given pair. This is used to indicate if only one contact point is provided which means nearest_points[0] must equal nearest_points[1].

Definition at line 125 of file types.h.

◆ subshape_id

std::array<int, 2> tesseract_collision::ContactResult::subshape_id { -1, -1 }

Some shapes like octomap and mesh have subshape (boxes and triangles)

Definition at line 96 of file types.h.

◆ transform

std::array<Eigen::Isometry3d, 2> tesseract_collision::ContactResult::transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() }

The transform of link in world coordinates.

Definition at line 102 of file types.h.

◆ type_id

std::array<int, 2> tesseract_collision::ContactResult::type_id { 0, 0 }

A user defined type id that is added to the contact shapes.

Definition at line 90 of file types.h.


The documentation for this struct was generated from the following files:
tesseract_collision::ContinuousCollisionType::CCType_None
@ CCType_None


tesseract_collision
Author(s): Levi Armstrong
autogenerated on Sun May 18 2025 03:01:53