|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Classes | |
| class | CollisionLinearModel |
| class | SortFilterProxyModel |
| class | CollisionMatrixModel |
| struct | LinkPairData |
| Store details on a pair of links. More... | |
| class | DefaultCollisions |
| class | DefaultCollisionsWidget |
| User interface for editing the default collision matrix list in an SRDF. More... | |
| class | MonitorThread |
| QThread to monitor progress of the setup step. More... | |
| class | EndEffectors |
| class | EndEffectorsWidget |
| class | GroupEditWidget |
| struct | GroupMetaData |
| class | GroupMetaConfig |
| class | KinematicChainWidget |
| class | PassiveJoints |
| class | PassiveJointsWidget |
| class | LinkNameTree |
| class | PlanningGroups |
| class | PlanningGroupsWidget |
| class | PlanGroupType |
| class | RobotPoses |
| class | RobotPosesWidget |
| class | SliderWidget |
| class | RotatedHeaderView |
| class | SRDFStep |
| Setup Step that contains the SRDFConfig. More... | |
| class | SuperSRDFStep |
| This class provides a number of standard operations based on srdf's vector members. More... | |
| class | VirtualJoints |
| class | VirtualJointsWidget |
| struct | ThreadComputation |
| struct | CycleDetector |
Typedefs | |
| 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::map< const moveit::core::LinkModel *, std::set< const moveit::core::LinkModel * > > | LinkGraph |
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 | |
| 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... | |
| const std::string | disabledReasonToString (DisabledReason reason) |
| Converts a reason for disabling a link pair into a string. More... | |
| DisabledReason | disabledReasonFromString (const std::string &reason) |
| Converts a string reason for disabling a link pair into a struct data type. More... | |
| LinkNameTree | buildLinkNameTree (const moveit::core::LinkModel *link) |
| bool | compareVariants (const QVariant &left, const QVariant &right) |
Variables | |
| const std::unordered_map< DisabledReason, std::string > | REASONS_TO_STRING |
| const std::unordered_map< std::string, DisabledReason > | REASONS_FROM_STRING |
| typedef std::map<const moveit::core::LinkModel*, std::set<const moveit::core::LinkModel*> > moveit_setup::srdf_setup::LinkGraph |
Definition at line 90 of file compute_default_collisions.cpp.
| typedef std::map<std::pair<std::string, std::string>, LinkPairData> moveit_setup::srdf_setup::LinkPairMap |
LinkPairMap is an adjacency list structure containing links in string-based form. Used for disabled links.
Definition at line 78 of file compute_default_collisions.hpp.
| typedef std::set<std::pair<std::string, std::string> > moveit_setup::srdf_setup::StringPairSet |
Definition at line 63 of file compute_default_collisions.cpp.
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 54 of file compute_default_collisions.hpp.
| Enumerator | |
|---|---|
| JOINT | |
| LINK | |
| CHAIN | |
| SUBGROUP | |
| GROUP | |
Definition at line 60 of file planning_groups_widget.hpp.
|
inline |
Definition at line 54 of file planning_groups.hpp.


| bool moveit_setup::srdf_setup::compareVariants | ( | const QVariant & | left, |
| const QVariant & | right | ||
| ) |
Definition at line 256 of file collision_linear_model.cpp.

| LinkPairMap moveit_setup::srdf_setup::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 176 of file compute_default_collisions.cpp.


| void moveit_setup::srdf_setup::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 325 of file compute_default_collisions.cpp.

| DisabledReason moveit_setup::srdf_setup::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 658 of file compute_default_collisions.cpp.

| const std::string moveit_setup::srdf_setup::disabledReasonToString | ( | DisabledReason | reason | ) |
Converts a reason for disabling a link pair into a string.
| reason | enum reason type |
Definition at line 650 of file compute_default_collisions.cpp.

| const std::unordered_map<std::string, DisabledReason> moveit_setup::srdf_setup::REASONS_FROM_STRING |
Definition at line 56 of file compute_default_collisions.cpp.
| const std::unordered_map<DisabledReason, std::string> moveit_setup::srdf_setup::REASONS_TO_STRING |
Definition at line 53 of file compute_default_collisions.cpp.