Classes | |
class | CheckboxSortWidgetItem |
Subclass QTableWidgetItem for checkboxes to allow custom sorting by implementing the < operator. More... | |
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 | GroupEditWidget |
struct | GroupMetaData |
class | HeaderWidget |
class | ik_solver_base |
class | ikfast_solver |
class | KinematicChainWidget |
struct | LinkPairData |
Store details on a pair of links. More... | |
class | LoadPathWidget |
class | MoveItConfigData |
class | NavDelegate |
class | NavigationWidget |
class | PassiveJointsWidget |
class | PlanningGroupsWidget |
class | RobotPosesWidget |
class | SelectModeWidget |
class | SetupAssistantWidget |
class | SliderWidget |
class | SRDFWriter |
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. | |
typedef boost::shared_ptr < MoveItConfigData > | MoveItConfigDataPtr |
Create a shared pointer for passing this data object between widgets. | |
typedef boost::shared_ptr < SRDFWriter > | SRDFWriterPtr |
Create a shared pointer for passing this data object between widgets. | |
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. | |
static void | computeConnectionGraphRec (const robot_model::LinkModel *link, LinkGraph &link_graph) |
Recursively build the adj list of link connections. | |
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. | |
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. | |
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. | |
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. | |
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. | |
DisabledReason | disabledReasonFromString (const std::string &reason) |
Converts a string reason for disabling a link pair into a struct data type. | |
const std::string | disabledReasonToString (DisabledReason reason) |
Converts a reason for disabling a link pair into a string. | |
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. | |
static void | disableNeverInCollisionThread (ThreadComputation tc) |
Thread for getting the pairs of links that are never in collision. | |
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. | |
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 |
const boost::unordered_map < moveit_setup_assistant::DisabledReason, const char * > | longReasonsToString |
Boost mapping of reasons for disabling a link pair to strings. | |
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" |
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 100 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 65 of file compute_default_collisions.h.
typedef boost::shared_ptr<MoveItConfigData> moveit_setup_assistant::MoveItConfigDataPtr |
Create a shared pointer for passing this data object between widgets.
Definition at line 231 of file moveit_config_data.h.
typedef boost::shared_ptr<SRDFWriter> moveit_setup_assistant::SRDFWriterPtr |
Create a shared pointer for passing this data object between widgets.
Definition at line 189 of file srdf_writer.h.
typedef std::set<std::pair<std::string, std::string> > moveit_setup_assistant::StringPairSet |
Definition at line 72 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.
Definition at line 49 of file compute_default_collisions.h.
Definition at line 63 of file planning_groups_widget.h.
void moveit_setup_assistant::computeConnectionGraph | ( | const robot_model::LinkModel * | link, |
LinkGraph & | link_graph | ||
) | [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 352 of file compute_default_collisions.cpp.
void moveit_setup_assistant::computeConnectionGraphRec | ( | const robot_model::LinkModel * | link, |
LinkGraph & | link_graph | ||
) | [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 406 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 188 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 332 of file compute_default_collisions.cpp.
unsigned int moveit_setup_assistant::disableAdjacentLinks | ( | planning_scene::PlanningScene & | scene, |
LinkGraph & | link_graph, | ||
LinkPairMap & | link_pairs | ||
) | [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 432 of file compute_default_collisions.cpp.
unsigned int moveit_setup_assistant::disableAlwaysInCollision | ( | planning_scene::PlanningScene & | scene, |
LinkPairMap & | link_pairs, | ||
collision_detection::CollisionRequest & | req, | ||
StringPairSet & | links_seen_colliding, | ||
double | min_collision_faction = 0.95 |
||
) | [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 491 of file compute_default_collisions.cpp.
unsigned int moveit_setup_assistant::disableDefaultCollisions | ( | planning_scene::PlanningScene & | scene, |
LinkPairMap & | link_pairs, | ||
collision_detection::CollisionRequest & | req | ||
) | [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 463 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 666 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 658 of file compute_default_collisions.cpp.
unsigned int moveit_setup_assistant::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 | ||
) | [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 567 of file compute_default_collisions.cpp.
void moveit_setup_assistant::disableNeverInCollisionThread | ( | ThreadComputation | tc | ) | [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 613 of file compute_default_collisions.cpp.
bool moveit_setup_assistant::setLinkPair | ( | const std::string & | linkA, |
const std::string & | linkB, | ||
const DisabledReason | reason, | ||
LinkPairMap & | link_pairs | ||
) | [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 295 of file compute_default_collisions.cpp.
const int moveit_setup_assistant::DEFAULT_KIN_SOLVER_ATTEMPTS_ = 3 [static] |
Definition at line 61 of file moveit_config_data.h.
const double moveit_setup_assistant::DEFAULT_KIN_SOLVER_SEARCH_RESOLUTION_ = 0.005 [static] |
Definition at line 59 of file moveit_config_data.h.
const double moveit_setup_assistant::DEFAULT_KIN_SOLVER_TIMEOUT_ = 0.005 [static] |
Definition at line 60 of file moveit_config_data.h.
const boost::unordered_map<moveit_setup_assistant::DisabledReason, const char*> moveit_setup_assistant::longReasonsToString |
boost::assign::map_list_of ( moveit_setup_assistant::NEVER, "Never in Collision" ) ( moveit_setup_assistant::DEFAULT, "Collision by Default" ) ( moveit_setup_assistant::ADJACENT, "Adjacent Links" ) ( moveit_setup_assistant::ALWAYS, "Always in Collision" ) ( moveit_setup_assistant::USER, "User Disabled" ) ( moveit_setup_assistant::NOT_DISABLED, "")
Boost mapping of reasons for disabling a link pair to strings.
Definition at line 53 of file default_collisions_widget.cpp.
const std::string moveit_setup_assistant::MOVEIT_ROBOT_STATE = "moveit_robot_state" [static] |
Definition at line 56 of file moveit_config_data.h.
const boost::unordered_map< std::string, DisabledReason> moveit_setup_assistant::reasonsFromString |
boost::assign::map_list_of ( "Never", NEVER ) ( "Default", DEFAULT ) ( "Adjacent", ADJACENT ) ( "Always", ALWAYS ) ( "User", USER ) ( "Not Disabled", NOT_DISABLED )
Definition at line 62 of file compute_default_collisions.cpp.
const boost::unordered_map<DisabledReason, std::string> moveit_setup_assistant::reasonsToString |
boost::assign::map_list_of ( NEVER, "Never" ) ( DEFAULT, "Default" ) ( ADJACENT, "Adjacent" ) ( ALWAYS, "Always" ) ( USER, "User" ) ( NOT_DISABLED, "Not Disabled")
Definition at line 54 of file compute_default_collisions.cpp.
const std::string moveit_setup_assistant::ROBOT_DESCRIPTION = "robot_description" [static] |
Definition at line 55 of file moveit_config_data.h.
const std::string moveit_setup_assistant::VIS_TOPIC_NAME = "planning_components_visualization" [static] |
Definition at line 77 of file planning_groups_widget.cpp.