Public Member Functions | Public Attributes | List of all members
collision_detection::GroupStateRepresentation Struct Reference

#include <collision_common_distance_field.h>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW GroupStateRepresentation ()
 
 GroupStateRepresentation (const GroupStateRepresentation &gsr)
 

Public Attributes

std::vector< PosedBodySphereDecompositionVectorPtr > attached_body_decompositions_
 
DistanceFieldCacheEntryConstPtr dfce_
 
std::vector< GradientInfogradients_
 
std::vector< PosedBodySphereDecompositionPtr > link_body_decompositions_
 
std::vector< PosedDistanceFieldPtr > link_distance_fields_
 

Detailed Description

collision volume representation for a particular pose and link group

This stores posed spheres making up the collision volume for a particular link group in a particular pose. It is associated with a particular dfce_ and can only be used with that dfce_ (DistanceFieldCacheEntry – see below).

Definition at line 88 of file collision_common_distance_field.h.

Constructor & Destructor Documentation

◆ GroupStateRepresentation() [1/2]

EIGEN_MAKE_ALIGNED_OPERATOR_NEW collision_detection::GroupStateRepresentation::GroupStateRepresentation ( )
inline

Definition at line 92 of file collision_common_distance_field.h.

◆ GroupStateRepresentation() [2/2]

collision_detection::GroupStateRepresentation::GroupStateRepresentation ( const GroupStateRepresentation gsr)
inline

Definition at line 93 of file collision_common_distance_field.h.

Member Data Documentation

◆ attached_body_decompositions_

std::vector<PosedBodySphereDecompositionVectorPtr> collision_detection::GroupStateRepresentation::attached_body_decompositions_

posed spheres representing collision volume for bodies attached to group links

Definition at line 126 of file collision_common_distance_field.h.

◆ dfce_

DistanceFieldCacheEntryConstPtr collision_detection::GroupStateRepresentation::dfce_

dfce used to generate this GSR

Definition at line 116 of file collision_common_distance_field.h.

◆ gradients_

std::vector<GradientInfo> collision_detection::GroupStateRepresentation::gradients_

information about detected collisions, collected during collision detection. One entry for each link and one entry for each attached object.

Definition at line 134 of file collision_common_distance_field.h.

◆ link_body_decompositions_

std::vector<PosedBodySphereDecompositionPtr> collision_detection::GroupStateRepresentation::link_body_decompositions_

posed spheres representing collision volume for the links in the group (dfce_.group_name_) and all links below the group (i.e. links that can move if joints in the group move). These are posed in the global frame used for collision detection.

Definition at line 122 of file collision_common_distance_field.h.

◆ link_distance_fields_

std::vector<PosedDistanceFieldPtr> collision_detection::GroupStateRepresentation::link_distance_fields_

Definition at line 129 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 Thu Apr 18 2024 02:23:41