#include <moveit/planning_scene/planning_scene.h>

Go to the source code of this file.
Classes | |
| struct | moveit_setup_assistant::LinkPairData |
| Store details on a pair of links. More... | |
Namespaces | |
| namespace | moveit_setup_assistant |
Typedefs | |
| typedef std::map< std::pair < std::string, std::string > , LinkPairData > | moveit_setup_assistant::LinkPairMap |
| LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled links. | |
Enumerations | |
| enum | moveit_setup_assistant::DisabledReason { moveit_setup_assistant::NEVER, moveit_setup_assistant::DEFAULT, moveit_setup_assistant::ADJACENT, moveit_setup_assistant::ALWAYS, moveit_setup_assistant::USER, moveit_setup_assistant::NOT_DISABLED } |
| Reasons for disabling link pairs. Append "in collision" for understanding. NOT_DISABLED means the link pair DOES do self collision checking. More... | |
Functions | |
| LinkPairMap | moveit_setup_assistant::computeDefaultCollisions (const planning_scene::PlanningSceneConstPtr &parent_scene, unsigned int *progress, const bool include_never_colliding, const unsigned int trials, const double min_collision_faction, const bool verbose) |
| Generate an adjacency list of links that are always and never in collision, to speed up collision detection. | |
| void | moveit_setup_assistant::computeLinkPairs (const planning_scene::PlanningScene &scene, LinkPairMap &link_pairs) |
| Generate a list of unique link pairs for all links with geometry. Order pairs alphabetically. n choose 2 pairs. | |
| DisabledReason | moveit_setup_assistant::disabledReasonFromString (const std::string &reason) |
| Converts a string reason for disabling a link pair into a struct data type. | |
| const std::string | moveit_setup_assistant::disabledReasonToString (DisabledReason reason) |
| Converts a reason for disabling a link pair into a string. | |