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