37 #ifndef MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_ 38 #define MOVEIT_COLLISION_DETECTION_DISTANCE_FIELD_COLLISION_COMMON_ 84 DistanceFieldCacheEntryConstPtr
dfce_;
181 visualization_msgs::MarkerArray& body_marker_array);
PosedBodySphereDecompositionVectorPtr getAttachedBodySphereDecomposition(const robot_state::AttachedBody *att, double resolution)
std::vector< PosedBodySphereDecompositionPtr > link_body_decompositions_
GroupStateRepresentation(const GroupStateRepresentation &gsr)
std::vector< GradientInfo > gradients_
robot_state::RobotStatePtr state_
void getBodySphereVisualizationMarkers(GroupStateRepresentationPtr &gsr, std::string reference_frame, visualization_msgs::MarkerArray &body_marker_array)
EIGEN_MAKE_ALIGNED_OPERATOR_NEW std::string group_name_
std::vector< unsigned int > attached_body_link_state_indices_
MOVEIT_CLASS_FORWARD(AllowedCollisionMatrix)
BodyDecompositionConstPtr getBodyDecompositionCacheEntry(const shapes::ShapeConstPtr &shape, double resolution)
std::vector< std::vector< bool > > intra_group_collision_enabled_
Generic interface to collision detection.
distance_field::DistanceFieldPtr distance_field_
std::vector< unsigned int > link_state_indices_
PosedBodyPointDecompositionVectorPtr getAttachedBodyPointDecomposition(const robot_state::AttachedBody *att, double resolution)
A representation of an object.
std::vector< std::string > attached_body_names_
static const double resolution
GroupStateRepresentationPtr pregenerated_group_state_representation_
std::vector< unsigned int > state_check_indices_
Definition of a structure for the allowed collision matrix. All elements in the collision world are r...
std::vector< unsigned int > link_body_indices_
std::vector< bool > link_has_geometry_
ROS/KDL based interface for the inverse kinematics of the PR2 arm.
PosedBodyPointDecompositionVectorPtr getCollisionObjectPointDecomposition(const collision_detection::World::Object &obj, double resolution)
std::vector< bool > self_collision_enabled_
std::vector< std::string > link_names_
std::vector< PosedBodySphereDecompositionVectorPtr > attached_body_decompositions_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW GroupStateRepresentation()
std::vector< double > state_values_
std::vector< PosedDistanceFieldPtr > link_distance_fields_
DistanceFieldCacheEntryConstPtr dfce_
Object defining bodies that can be attached to robot links. This is useful when handling objects pick...
collision_detection::AllowedCollisionMatrix acm_
std::shared_ptr< const Shape > ShapeConstPtr