Classes | |
| struct | Attribute |
| class | AuthorInformationWidget |
| class | ConfigurationFilesWidget |
| struct | ControllerConfig |
| class | ControllerEditWidget |
| class | ControllersWidget |
| struct | CycleDetector |
| class | DefaultCollisionsWidget |
| User interface for editing the default collision matrix list in an SRDF. More... | |
| class | DoubleListWidget |
| class | EndEffectorsWidget |
| struct | GenerateFile |
| class | GenericParameter |
| class | GroupEditWidget |
| struct | GroupMetaData |
| class | HeaderWidget |
| class | KinematicChainWidget |
| struct | LinkPairData |
| Store details on a pair of links. More... | |
| class | LoadPathArgsWidget |
| Extend LoadPathWidget with additional line edit for arguments. More... | |
| class | LoadPathWidget |
| class | MonitorThread |
| class | MoveItConfigData |
| This class is shared with all widgets and contains the common configuration data needed for generating each robot's MoveIt configuration package. More... | |
| class | NavDelegate |
| class | NavigationWidget |
| class | OMPLPlannerDescription |
| This class describes the OMPL planners by name, type, and parameter list, used to create the ompl_planning.yaml file. More... | |
| struct | OmplPlanningParameter |
| class | PassiveJointsWidget |
| class | PerceptionWidget |
| class | PlanningGroupsWidget |
| class | RobotPosesWidget |
| class | RotatedHeaderView |
| class | SelectModeWidget |
| class | SetupAssistantWidget |
| class | SimulationWidget |
| class | SliderWidget |
| class | StartScreenWidget |
| Start screen user interface for MoveIt Configuration Assistant. More... | |
| struct | ThreadComputation |
| class | VirtualJointsWidget |
Typedefs | |
| typedef std::map< const moveit::core::LinkModel *, std::set< const moveit::core::LinkModel * > > | LinkGraph |
| typedef std::map< std::pair< std::string, std::string >, LinkPairData > | LinkPairMap |
| LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled links. More... | |
| typedef std::set< std::pair< std::string, std::string > > | StringPairSet |
| typedef std::vector< std::pair< std::string, std::string > > | StringPairVector |
Enumerations | |
| enum | DisabledReason { NEVER, DEFAULT, ADJACENT, ALWAYS, USER, NOT_DISABLED } |
| Reasons for disabling link pairs. Append "in collision" for understanding. NOT_DISABLED means the link pair DOES do self collision checking. More... | |
| enum | GroupType { JOINT = 1, LINK = 2, CHAIN = 3, SUBGROUP = 4, GROUP = 5 } |
Functions | |
| static void | computeConnectionGraph (const moveit::core::LinkModel *link, LinkGraph &link_graph) |
| Build the robot links connection graph and then check for links with no geomotry. More... | |
| static void | computeConnectionGraphRec (const moveit::core::LinkModel *link, LinkGraph &link_graph) |
| Recursively build the adj list of link connections. More... | |
| LinkPairMap | 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. More... | |
| void | 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. More... | |
| static unsigned int | disableAdjacentLinks (planning_scene::PlanningScene &scene, LinkGraph &link_graph, LinkPairMap &link_pairs) |
| Disable collision checking for adjacent links, or adjacent with no geometry links between them. More... | |
| static unsigned int | disableAlwaysInCollision (planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, collision_detection::CollisionRequest &req, StringPairSet &links_seen_colliding, double min_collision_faction=0.95) |
| Compute the links that are always in collision. More... | |
| static unsigned int | disableDefaultCollisions (planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, collision_detection::CollisionRequest &req) |
| Disable all collision checks that occur when the robot is started in its default state. More... | |
| DisabledReason | disabledReasonFromString (const std::string &reason) |
| Converts a string reason for disabling a link pair into a struct data type. More... | |
| const std::string | disabledReasonToString (DisabledReason reason) |
| Converts a reason for disabling a link pair into a string. More... | |
| static unsigned int | disableNeverInCollision (const unsigned int num_trials, planning_scene::PlanningScene &scene, LinkPairMap &link_pairs, const collision_detection::CollisionRequest &req, StringPairSet &links_seen_colliding, unsigned int *progress) |
| Get the pairs of links that are never in collision. More... | |
| static void | disableNeverInCollisionThread (ThreadComputation tc) |
| Thread for getting the pairs of links that are never in collision. More... | |
| MOVEIT_CLASS_FORWARD (MoveItConfigData) | |
| template<typename T > | |
| bool | parse (const YAML::Node &node, const std::string &key, T &storage, const T &default_value=T()) |
| static bool | setLinkPair (const std::string &linkA, const std::string &linkB, const DisabledReason reason, LinkPairMap &link_pairs) |
| Helper function for adding two links to the disabled links data structure. More... | |
| TiXmlElement * | uniqueInsert (TiXmlElement &element, const char *tag, const std::vector< Attribute > &attributes={}, const char *text=nullptr) |
Variables | |
| static const std::string | CONFIG_PATH = "config" |
| static const double | DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION = 0.005 |
| static const double | DEFAULT_KIN_SOLVER_TIMEOUT = 0.005 |
| static const std::string | MOVEIT_ROBOT_STATE = "moveit_robot_state" |
| const boost::unordered_map< std::string, DisabledReason > | REASONS_FROM_STRING |
| const boost::unordered_map< DisabledReason, std::string > | REASONS_TO_STRING |
| static const std::string | ROBOT_DESCRIPTION = "robot_description" |
| static const std::string | SETUP_ASSISTANT_FILE = ".setup_assistant" |
| static const std::string | VIS_TOPIC_NAME = "planning_components_visualization" |
| typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> > moveit_setup_assistant::LinkGraph |
Definition at line 119 of file compute_default_collisions.cpp.
| 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.
Definition at line 76 of file compute_default_collisions.h.
| typedef std::set<std::pair<std::string, std::string> > moveit_setup_assistant::StringPairSet |
Definition at line 92 of file compute_default_collisions.cpp.
| typedef std::vector<std::pair<std::string, std::string> > moveit_setup_assistant::StringPairVector |
Definition at line 72 of file configuration_files_widget.h.
Reasons for disabling link pairs. Append "in collision" for understanding. NOT_DISABLED means the link pair DOES do self collision checking.
| Enumerator | |
|---|---|
| NEVER | |
| DEFAULT | |
| ADJACENT | |
| ALWAYS | |
| USER | |
| NOT_DISABLED | |
Definition at line 52 of file compute_default_collisions.h.
| Enumerator | |
|---|---|
| JOINT | |
| LINK | |
| CHAIN | |
| SUBGROUP | |
| GROUP | |
Definition at line 62 of file planning_groups_widget.h.
|
static |
Build the robot links connection graph and then check for links with no geomotry.
| link | The root link to begin a breadth first search on |
| link_graph | A representation of all bi-direcitonal joint connections between links in robot_description |
Definition at line 372 of file compute_default_collisions.cpp.
|
static |
Recursively build the adj list of link connections.
| link | The root link to begin a breadth first search on |
| link_graph | A representation of all bi-direcitonal joint connections between links in robot_description |
Definition at line 423 of file compute_default_collisions.cpp.
| 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.
| parent_scene | A reference to the robot in the planning scene |
| include_never_colliding | Flag to disable the check for links that are never in collision |
| trials | Set the number random collision checks that are made. Increase the probability of correctness |
| min_collision_fraction | If collisions are found between a pair of links >= this fraction, the are assumed "always" in collision |
Definition at line 205 of file compute_default_collisions.cpp.
| 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.
| scene | A reference to the robot in the planning scene |
| link_pairs | List of all unique link pairs and each pair's properties |
Definition at line 352 of file compute_default_collisions.cpp.
|
static |
Disable collision checking for adjacent links, or adjacent with no geometry links between them.
| link_graph | A representation of all bi-direcitonal joint connections between links in robot_description |
| scene | A reference to the robot in the planning scene |
| link_pairs | List of all unique link pairs and each pair's properties |
Definition at line 449 of file compute_default_collisions.cpp.
|
static |
Compute the links that are always in collision.
| scene | A reference to the robot in the planning scene |
| link_pairs | List of all unique link pairs and each pair's properties |
| req | A reference to a collision request that is already initialized |
| links_seen_colliding | Set of links that have at some point been seen in collision |
| min_collision_fraction | If collisions are found between a pair of links >= this fraction, the are assumed "always" in collision |
Definition at line 506 of file compute_default_collisions.cpp.
|
static |
Disable all collision checks that occur when the robot is started in its default state.
| scene | A reference to the robot in the planning scene |
| link_pairs | List of all unique link pairs and each pair's properties |
| req | A reference to a collision request that is already initialized |
Definition at line 478 of file compute_default_collisions.cpp.
| DisabledReason moveit_setup_assistant::disabledReasonFromString | ( | const std::string & | reason | ) |
Converts a string reason for disabling a link pair into a struct data type.
| reason | string that should match one of the DisableReason types. If not, is set as "USER" |
Definition at line 693 of file compute_default_collisions.cpp.
| const std::string moveit_setup_assistant::disabledReasonToString | ( | DisabledReason | reason | ) |
Converts a reason for disabling a link pair into a string.
| reason | enum reason type |
Definition at line 685 of file compute_default_collisions.cpp.
|
static |
Get the pairs of links that are never in collision.
| scene | A reference to the robot in the planning scene |
| link_pairs | List of all unique link pairs and each pair's properties |
| req | A reference to a collision request that is already initialized |
| links_seen_colliding | Set of links that have at some point been seen in collision |
Definition at line 581 of file compute_default_collisions.cpp.
|
static |
Thread for getting the pairs of links that are never in collision.
| tc | Struct that encapsulates all the data each thread needs |
Definition at line 638 of file compute_default_collisions.cpp.
| moveit_setup_assistant::MOVEIT_CLASS_FORWARD | ( | MoveItConfigData | ) |
| bool moveit_setup_assistant::parse | ( | const YAML::Node & | node, |
| const std::string & | key, | ||
| T & | storage, | ||
| const T & | default_value = T() |
||
| ) |
Definition at line 1367 of file moveit_config_data.cpp.
|
static |
Helper function for adding two links to the disabled links data structure.
| linkA | Name of first link |
| linkB | Name of second link |
| reason | Enum reason of why the link pair is disabled from C.C., if it is |
| link_pairs | List of all unique link pairs and each pair's properties |
Definition at line 315 of file compute_default_collisions.cpp.
| TiXmlElement * moveit_setup_assistant::uniqueInsert | ( | TiXmlElement & | element, |
| const char * | tag, | ||
| const std::vector< Attribute > & | attributes = {}, |
||
| const char * | text = nullptr |
||
| ) |
Insert a new XML element with given tag, attributes and text value
If a corresponding element already exists (and has required attribute values), it is just reused. All attributes are created or overwritten with given values. A text value is created or overwritten with given value (if not NULL). The element is returned
Definition at line 91 of file xml_manipulation.cpp.
|
static |
Definition at line 100 of file configuration_files_widget.cpp.
|
static |
Definition at line 90 of file moveit_config_data.h.
|
static |
Definition at line 91 of file moveit_config_data.h.
|
static |
Definition at line 87 of file moveit_config_data.h.
| const boost::unordered_map<std::string, DisabledReason> moveit_setup_assistant::REASONS_FROM_STRING |
Definition at line 87 of file compute_default_collisions.cpp.
| const boost::unordered_map<DisabledReason, std::string> moveit_setup_assistant::REASONS_TO_STRING |
Definition at line 84 of file compute_default_collisions.cpp.
|
static |
Definition at line 86 of file moveit_config_data.h.
|
static |
Definition at line 99 of file configuration_files_widget.cpp.
|
static |
Definition at line 109 of file planning_groups_widget.cpp.