moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <default_collisions.hpp>
Public Member Functions | |
std::string | getName () const override |
Returns the name of the setup step. More... | |
std::vector< std::string > | getCollidingLinks () |
void | linkPairsToSRDF () |
Output Link Pairs to SRDF Format. More... | |
void | linkPairsToSRDFSorted (size_t skip_mask=0) |
Output Link Pairs to SRDF Format; sorted; with optional filter. More... | |
void | linkPairsFromSRDF () |
Load Link Pairs from SRDF Format. More... | |
LinkPairMap & | getLinkPairs () |
void | startGenerationThread (unsigned int num_trials, double min_frac, bool verbose=true) |
void | cancelGenerationThread () |
void | joinGenerationThread () |
int | getThreadProgress () const |
Public Member Functions inherited from moveit_setup::srdf_setup::SRDFStep | |
void | onInit () override |
Overridable initialization method. More... | |
bool | isReady () const override |
Return true if the data necessary to proceed with this step has been configured. More... | |
bool | hasGroups () const |
Public Member Functions inherited from moveit_setup::SetupStep | |
SetupStep ()=default | |
SetupStep (const SetupStep &)=default | |
SetupStep (SetupStep &&)=default | |
SetupStep & | operator= (const SetupStep &)=default |
SetupStep & | operator= (SetupStep &&)=default |
virtual | ~SetupStep ()=default |
void | initialize (const rclcpp::Node::SharedPtr &parent_node, const DataWarehousePtr &config_data) |
Called after construction to initialize the step. More... | |
const rclcpp::Logger & | getLogger () const |
Makes a namespaced logger for this step available to the widget. More... | |
Protected Member Functions | |
void | generateCollisionTable (unsigned int num_trials, double min_frac, bool verbose) |
Protected Attributes | |
LinkPairMap | link_pairs_ |
main storage of link pair data More... | |
boost::thread | worker_ |
unsigned int | progress_ |
Protected Attributes inherited from moveit_setup::srdf_setup::SRDFStep | |
std::shared_ptr< SRDFConfig > | srdf_config_ |
Protected Attributes inherited from moveit_setup::SetupStep | |
DataWarehousePtr | config_data_ |
rclcpp::Node::SharedPtr | parent_node_ |
std::shared_ptr< rclcpp::Logger > | logger_ |
Definition at line 56 of file default_collisions.hpp.
void moveit_setup::srdf_setup::DefaultCollisions::cancelGenerationThread | ( | ) |
|
protected |
Definition at line 158 of file default_collisions.cpp.
std::vector< std::string > moveit_setup::srdf_setup::DefaultCollisions::getCollidingLinks | ( | ) |
Definition at line 43 of file default_collisions.cpp.
|
inline |
Definition at line 82 of file default_collisions.hpp.
|
inlineoverridevirtual |
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 59 of file default_collisions.hpp.
int moveit_setup::srdf_setup::DefaultCollisions::getThreadProgress | ( | ) | const |
void moveit_setup::srdf_setup::DefaultCollisions::joinGenerationThread | ( | ) |
void moveit_setup::srdf_setup::DefaultCollisions::linkPairsFromSRDF | ( | ) |
Load Link Pairs from SRDF Format.
Definition at line 113 of file default_collisions.cpp.
void moveit_setup::srdf_setup::DefaultCollisions::linkPairsToSRDF | ( | ) |
Output Link Pairs to SRDF Format.
Definition at line 50 of file default_collisions.cpp.
void moveit_setup::srdf_setup::DefaultCollisions::linkPairsToSRDFSorted | ( | size_t | skip_mask = 0 | ) |
Output Link Pairs to SRDF Format; sorted; with optional filter.
skip_mask | mask of shifted DisabledReason values that will be skipped |
Definition at line 74 of file default_collisions.cpp.
void moveit_setup::srdf_setup::DefaultCollisions::startGenerationThread | ( | unsigned int | num_trials, |
double | min_frac, | ||
bool | verbose = true |
||
) |
|
protected |
main storage of link pair data
Definition at line 97 of file default_collisions.hpp.
|
protected |
Definition at line 101 of file default_collisions.hpp.
|
protected |
Definition at line 100 of file default_collisions.hpp.