Classes | |
class | AuthorInformationWidget |
class | ConfigurationFilesWidget |
struct | cycle_detector |
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 |
QThread to monitor progress of a boost::thread. More... | |
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 |
struct | ROSControlConfig |
class | RotatedHeaderView |
class | SelectModeWidget |
class | SetupAssistantWidget |
class | SimulationWidget |
class | SliderWidget |
class | SortableDisabledCollision |
class | StartScreenWidget |
Start screen user interface for MoveIt! Configuration Assistant. More... | |
struct | ThreadComputation |
class | VirtualJointsWidget |
Typedefs | |
typedef std::map< const robot_model::LinkModel *, std::set< const robot_model::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, LINK, CHAIN, SUBGROUP, GROUP } |
Functions | |
static void | computeConnectionGraph (const robot_model::LinkModel *link, LinkGraph &link_graph) |
Build the robot links connection graph and then check for links with no geomotry. More... | |
static void | computeConnectionGraphRec (const robot_model::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... | |
Variables | |
static const int | DEFAULT_KIN_SOLVER_ATTEMPTS_ = 3 |
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 > | reasonsFromString |
const boost::unordered_map< DisabledReason, std::string > | reasonsToString |
static const std::string | ROBOT_DESCRIPTION = "robot_description" |
const std::string | SETUP_ASSISTANT_FILE = ".setup_assistant" |
static const std::string | VIS_TOPIC_NAME = "planning_components_visualization" |
typedef std::map<const robot_model::LinkModel*, std::set<const robot_model::LinkModel*> > moveit_setup_assistant::LinkGraph |
Definition at line 86 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 72 of file compute_default_collisions.h.
typedef std::set<std::pair<std::string, std::string> > moveit_setup_assistant::StringPairSet |
Definition at line 59 of file compute_default_collisions.cpp.
typedef std::vector<std::pair<std::string, std::string> > moveit_setup_assistant::StringPairVector |
Definition at line 73 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 48 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 341 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 393 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 172 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 321 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 419 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 476 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 448 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 663 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 655 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 551 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 608 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 1222 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 284 of file compute_default_collisions.cpp.
|
static |
Definition at line 63 of file moveit_config_data.h.
|
static |
Definition at line 61 of file moveit_config_data.h.
|
static |
Definition at line 62 of file moveit_config_data.h.
|
static |
Definition at line 58 of file moveit_config_data.h.
const boost::unordered_map<std::string, DisabledReason> moveit_setup_assistant::reasonsFromString |
Definition at line 55 of file compute_default_collisions.cpp.
const boost::unordered_map<DisabledReason, std::string> moveit_setup_assistant::reasonsToString |
Definition at line 52 of file compute_default_collisions.cpp.
|
static |
Definition at line 57 of file moveit_config_data.h.
const std::string moveit_setup_assistant::SETUP_ASSISTANT_FILE = ".setup_assistant" |
Definition at line 60 of file configuration_files_widget.cpp.
|
static |
Definition at line 76 of file planning_groups_widget.cpp.