moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
This class provides a number of standard operations based on srdf's vector members. More...
#include <srdf_step.hpp>
Public Member Functions | |
virtual std::vector< T > & | getContainer ()=0 |
Returns the reference to the vector in the SRDF. More... | |
virtual InformationFields | getInfoField () const =0 |
Returns the info field associated with this part of the SRDF. More... | |
T * | find (const std::string &name) |
Return a pointer to an item with the given name if it exists, otherwise null. More... | |
T * | create (const std::string &name) |
Create an item with the given name and return the pointer. More... | |
T * | rename (const std::string &old_name, const std::string &new_name) |
Renames an item and returns a pointer to the item. More... | |
bool | remove (const std::string &name) |
Delete an item with the given name from the list. More... | |
T * | get (const std::string &name, const std::string &old_name="") |
Get a pointer to an item with the given name, creating if necessary. If old_name is provided (and is different) will rename the given item. More... | |
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... | |
virtual std::string | getName () const =0 |
Returns the name of the setup step. More... | |
const rclcpp::Logger & | getLogger () const |
Makes a namespaced logger for this step available to the widget. More... | |
Additional Inherited Members | |
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_ |
This class provides a number of standard operations based on srdf's vector members.
Assuming T is a type that has a name_ field, this provides the following operations on the container in which the name_ field is kept unique.
Definition at line 82 of file srdf_step.hpp.
|
inline |
Create an item with the given name and return the pointer.
Definition at line 115 of file srdf_step.hpp.
|
inline |
Return a pointer to an item with the given name if it exists, otherwise null.
Definition at line 98 of file srdf_step.hpp.
|
inline |
Get a pointer to an item with the given name, creating if necessary. If old_name is provided (and is different) will rename the given item.
Definition at line 164 of file srdf_step.hpp.
|
pure virtual |
Returns the reference to the vector in the SRDF.
Implemented in moveit_setup::srdf_setup::VirtualJoints, moveit_setup::srdf_setup::PlanningGroups, and moveit_setup::srdf_setup::EndEffectors.
|
pure virtual |
Returns the info field associated with this part of the SRDF.
Implemented in moveit_setup::srdf_setup::VirtualJoints, moveit_setup::srdf_setup::PlanningGroups, and moveit_setup::srdf_setup::EndEffectors.
|
inline |
Delete an item with the given name from the list.
Definition at line 145 of file srdf_step.hpp.
|
inline |
Renames an item and returns a pointer to the item.
runtime_error | If an item exists with the new name |
Definition at line 128 of file srdf_step.hpp.