|
moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <passive_joints.hpp>


Public Member Functions | |
| std::string | getName () const override |
| Returns the name of the setup step. More... | |
| std::vector< std::string > | getActiveJoints () const |
| Return all active (non-fixed) joint names. More... | |
| std::vector< std::string > | getPassiveJoints () const |
| Return all passive joint names (according to srdf) More... | |
| std::string | getChildOfJoint (const std::string &joint_name) const |
| void | setPassiveJoints (const std::vector< std::string > &passive_joints) |
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... | |
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_ |
Definition at line 44 of file passive_joints.hpp.
| std::vector< std::string > moveit_setup::srdf_setup::PassiveJoints::getActiveJoints | ( | ) | const |
Return all active (non-fixed) joint names.
Definition at line 43 of file passive_joints.cpp.

|
inline |
Definition at line 62 of file passive_joints.hpp.
|
inlineoverridevirtual |
Returns the name of the setup step.
Implements moveit_setup::SetupStep.
Definition at line 47 of file passive_joints.hpp.
| std::vector< std::string > moveit_setup::srdf_setup::PassiveJoints::getPassiveJoints | ( | ) | const |
Return all passive joint names (according to srdf)
Definition at line 61 of file passive_joints.cpp.

| void moveit_setup::srdf_setup::PassiveJoints::setPassiveJoints | ( | const std::vector< std::string > & | passive_joints | ) |
Definition at line 71 of file passive_joints.cpp.