56 struct GroupStateRepresentation
58 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
64 for (
unsigned int i = 0; i < gsr.link_body_decompositions_.size(); i++)
66 if (gsr.link_body_decompositions_[i])
69 std::make_shared<PosedBodySphereDecomposition>(*gsr.link_body_decompositions_[i]);
76 for (
unsigned int i = 0; i < gsr.attached_body_decompositions_.size(); i++)
84 DistanceFieldCacheEntryConstPtr
dfce_;
111 struct DistanceFieldCacheEntry
113 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
118 moveit::core::RobotStatePtr
state_;
181 visualization_msgs::MarkerArray& body_marker_array);