Public Attributes | List of all members
collision_detection::DistanceFieldCacheEntry Struct Reference

#include <collision_common_distance_field.h>

Public Attributes

collision_detection::AllowedCollisionMatrix acm_
 
std::vector< unsigned int > attached_body_link_state_indices_
 
std::vector< std::string > attached_body_names_
 
distance_field::DistanceFieldPtr distance_field_
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string group_name_
 
std::vector< std::vector< bool > > intra_group_collision_enabled_
 
std::vector< unsigned int > link_body_indices_
 
std::vector< bool > link_has_geometry_
 
std::vector< std::string > link_names_
 
std::vector< unsigned int > link_state_indices_
 
GroupStateRepresentationPtr pregenerated_group_state_representation_
 
std::vector< bool > self_collision_enabled_
 
robot_state::RobotStatePtr state_
 
std::vector< unsigned int > state_check_indices_
 
std::vector< double > state_values_
 

Detailed Description

collision volume representation for a particular link group of a robot

This entry is specific to a particular robot model, a particular link group, a particular ACM, and a particular configuration of attached objects. It assumes the poses of joints above this group have not changed, but can be used with different poses of the joints within the group.

Definition at line 111 of file collision_common_distance_field.h.

Member Data Documentation

collision_detection::AllowedCollisionMatrix collision_detection::DistanceFieldCacheEntry::acm_

Definition at line 131 of file collision_common_distance_field.h.

std::vector<unsigned int> collision_detection::DistanceFieldCacheEntry::attached_body_link_state_indices_

for each body in attached_body_names_, the index into the link state of the link the body is attached to.

Definition at line 157 of file collision_common_distance_field.h.

std::vector<std::string> collision_detection::DistanceFieldCacheEntry::attached_body_names_

list of all bodies attached to links in link_names_

Definition at line 154 of file collision_common_distance_field.h.

distance_field::DistanceFieldPtr collision_detection::DistanceFieldCacheEntry::distance_field_

the distance field describing all links of the robot that are not in the group and their attached bodies

Definition at line 134 of file collision_common_distance_field.h.

EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string collision_detection::DistanceFieldCacheEntry::group_name_

for checking collisions between this group and other objects

Definition at line 116 of file collision_common_distance_field.h.

std::vector<std::vector<bool> > collision_detection::DistanceFieldCacheEntry::intra_group_collision_enabled_

for each link in link_names_, a vector of bool indicating for each other object (where object could be another link or an attacjed object) whether to check for collisions between this link and that object. Size of inner and outer lists are the same and equal the sum of the size of link_names_ and attached_body_names_

Definition at line 166 of file collision_common_distance_field.h.

std::vector<unsigned int> collision_detection::DistanceFieldCacheEntry::link_body_indices_

for each link in link_names_, index into the CollisionRobotDistanceField::link_body_decomposition_vector_ vector. This is 0 (and invalid) for links with no geometry. The link_body_decomposition_vector_ contains the (unposed) spheres that make up the collision geometry for the link

Definition at line 149 of file collision_common_distance_field.h.

std::vector<bool> collision_detection::DistanceFieldCacheEntry::link_has_geometry_

for each link in link_names_, true if the link has collision geometry

Definition at line 143 of file collision_common_distance_field.h.

std::vector<std::string> collision_detection::DistanceFieldCacheEntry::link_names_

names of all links in the group and all links below the group (links that will move if any of the joints in the group move)

Definition at line 141 of file collision_common_distance_field.h.

std::vector<unsigned int> collision_detection::DistanceFieldCacheEntry::link_state_indices_

for each link in link_names_, index into the RobotState::link_state_vector_

Definition at line 152 of file collision_common_distance_field.h.

GroupStateRepresentationPtr collision_detection::DistanceFieldCacheEntry::pregenerated_group_state_representation_

this can be used as a starting point for creating a GroupStateRepresentation needed for collision checking

Definition at line 137 of file collision_common_distance_field.h.

std::vector<bool> collision_detection::DistanceFieldCacheEntry::self_collision_enabled_

for each link in link_names_ and for each body in attached_body_names_, true if this link should be checked for self collision

Definition at line 160 of file collision_common_distance_field.h.

robot_state::RobotStatePtr collision_detection::DistanceFieldCacheEntry::state_

RobotState that this cache entry represents

Definition at line 118 of file collision_common_distance_field.h.

std::vector<unsigned int> collision_detection::DistanceFieldCacheEntry::state_check_indices_

list of indices into the state_values_ vector. One index for each joint variable which is NOT in the group or a child of the group. In other words, variables which should not change if only joints in the group move.

Definition at line 123 of file collision_common_distance_field.h.

std::vector<double> collision_detection::DistanceFieldCacheEntry::state_values_

all the joint variables from all the joints in the entire robot (whether in the group or not), excluding mimic joints. If 2 DistanceFieldCacheEntrys have identical state_values_ then they are equivalent (i.e. same robot state).

Definition at line 128 of file collision_common_distance_field.h.


The documentation for this struct was generated from the following file:


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Sun Oct 18 2020 13:16:34