Tesseract
Motion Planning Environment
|
#include <types.h>
Public Member Functions | |
ContactResult ()=default | |
void | clear () |
reset to default values More... | |
Public Attributes | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double | distance { std::numeric_limits<double>::max() } |
The distance between two links. More... | |
std::array< int, 2 > | type_id { 0, 0 } |
A user defined type id that is added to the contact shapes. More... | |
std::array< std::string, 2 > | link_names |
The two links that are in contact. 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... | |
std::array< int, 2 > | subshape_id { -1, -1 } |
Some shapes like octomap and mesh have subshape (boxes and triangles) 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... | |
std::array< Eigen::Isometry3d, 2 > | transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() } |
The transform of link in world 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< double, 2 > | cc_time { -1, -1 } |
This is between 0 and 1 indicating the point of contact. More... | |
std::array< ContinuousCollisionType, 2 > | cc_type |
The type of continuous 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... | |
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... | |
|
default |
void tesseract_collision::ContactResult::clear | ( | ) |
reset to default values
std::array<double, 2> tesseract_collision::ContactResult::cc_time { -1, -1 } |
This is between 0 and 1 indicating the point of contact.
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;.
std::array<ContinuousCollisionType, 2> tesseract_collision::ContactResult::cc_type |
The type of continuous contact.
EIGEN_MAKE_ALIGNED_OPERATOR_NEW double tesseract_collision::ContactResult::distance { std::numeric_limits<double>::max() } |
The distance between two links.
std::array<std::string, 2> tesseract_collision::ContactResult::link_names |
The two links that are in contact.
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.
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.
Eigen::Vector3d tesseract_collision::ContactResult::normal { Eigen::Vector3d::Zero() } |
The normal vector to move the two objects out of contact in world coordinates.
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.
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].
std::array<int, 2> tesseract_collision::ContactResult::subshape_id { -1, -1 } |
Some shapes like octomap and mesh have subshape (boxes and triangles)
std::array<Eigen::Isometry3d, 2> tesseract_collision::ContactResult::transform { Eigen::Isometry3d::Identity(), Eigen::Isometry3d::Identity() } |
The transform of link in world coordinates.
std::array<int, 2> tesseract_collision::ContactResult::type_id { 0, 0 } |
A user defined type id that is added to the contact shapes.