| 
    moveit2
    
   The MoveIt Motion Planning Framework for ROS 2. 
   | 
 
Class to define a robot configuration in space with the help of joint values. More...
#include <jointconfiguration.h>


Public Member Functions | |
| JointConfiguration () | |
| JointConfiguration (const std::string &group_name, const std::vector< double > &config, CreateJointNameFunc &&create_joint_name_func) | |
| JointConfiguration (const std::string &group_name, const std::vector< double > &config, const moveit::core::RobotModelConstPtr &robot_model) | |
| void | setJoint (const size_t index, const double value) | 
| double | getJoint (const size_t index) const | 
| const std::vector< double > | getJoints () const | 
| size_t | size () const | 
| moveit_msgs::msg::Constraints | toGoalConstraints () const override | 
| moveit_msgs::msg::RobotState | toMoveitMsgsRobotState () const override | 
| sensor_msgs::msg::JointState | toSensorMsg () const | 
| moveit::core::RobotState | toRobotState () const | 
| void | setCreateJointNameFunc (CreateJointNameFunc create_joint_name_func) | 
  Public Member Functions inherited from pilz_industrial_motion_planner_testutils::RobotConfiguration | |
| RobotConfiguration () | |
| RobotConfiguration (const std::string &group_name) | |
| RobotConfiguration (const std::string &group_name, const moveit::core::RobotModelConstPtr &robot_model) | |
| void | setRobotModel (moveit::core::RobotModelConstPtr robot_model) | 
| void | setGroupName (const std::string &group_name) | 
| std::string | getGroupName () const | 
| void | clearModel () | 
  Public Member Functions inherited from pilz_industrial_motion_planner_testutils::RobotStateMsgConvertible | |
| RobotStateMsgConvertible ()=default | |
| RobotStateMsgConvertible (const RobotStateMsgConvertible &)=default | |
| RobotStateMsgConvertible (RobotStateMsgConvertible &&)=default | |
| RobotStateMsgConvertible & | operator= (const RobotStateMsgConvertible &)=default | 
| RobotStateMsgConvertible & | operator= (RobotStateMsgConvertible &&)=default | 
| virtual | ~RobotStateMsgConvertible ()=default | 
  Public Member Functions inherited from pilz_industrial_motion_planner_testutils::GoalConstraintMsgConvertible | |
| GoalConstraintMsgConvertible ()=default | |
| GoalConstraintMsgConvertible (const GoalConstraintMsgConvertible &)=default | |
| GoalConstraintMsgConvertible (GoalConstraintMsgConvertible &&)=default | |
| GoalConstraintMsgConvertible & | operator= (const GoalConstraintMsgConvertible &)=default | 
| GoalConstraintMsgConvertible & | operator= (GoalConstraintMsgConvertible &&)=default | 
| virtual | ~GoalConstraintMsgConvertible ()=default | 
Additional Inherited Members | |
  Protected Attributes inherited from pilz_industrial_motion_planner_testutils::RobotConfiguration | |
| std::string | group_name_ | 
| moveit::core::RobotModelConstPtr | robot_model_ | 
Class to define a robot configuration in space with the help of joint values.
Definition at line 65 of file jointconfiguration.h.
| pilz_industrial_motion_planner_testutils::JointConfiguration::JointConfiguration | ( | ) | 
Definition at line 41 of file jointconfiguration.cpp.
| pilz_industrial_motion_planner_testutils::JointConfiguration::JointConfiguration | ( | const std::string & | group_name, | 
| const std::vector< double > & | config, | ||
| CreateJointNameFunc && | create_joint_name_func | ||
| ) | 
Definition at line 45 of file jointconfiguration.cpp.
| pilz_industrial_motion_planner_testutils::JointConfiguration::JointConfiguration | ( | const std::string & | group_name, | 
| const std::vector< double > & | config, | ||
| const moveit::core::RobotModelConstPtr & | robot_model | ||
| ) | 
Definition at line 51 of file jointconfiguration.cpp.
      
  | 
  inline | 
      
  | 
  inline | 
Definition at line 128 of file jointconfiguration.h.
      
  | 
  inline | 
Definition at line 138 of file jointconfiguration.h.
      
  | 
  inline | 
Definition at line 118 of file jointconfiguration.h.
      
  | 
  inline | 
      
  | 
  inlineoverridevirtual | 
Implements pilz_industrial_motion_planner_testutils::GoalConstraintMsgConvertible.
Definition at line 108 of file jointconfiguration.h.
      
  | 
  inlineoverridevirtual | 
Implements pilz_industrial_motion_planner_testutils::RobotStateMsgConvertible.
Definition at line 113 of file jointconfiguration.h.
| moveit::core::RobotState pilz_industrial_motion_planner_testutils::JointConfiguration::toRobotState | ( | ) | const | 
| sensor_msgs::msg::JointState pilz_industrial_motion_planner_testutils::JointConfiguration::toSensorMsg | ( | ) | const | 
Definition at line 128 of file jointconfiguration.cpp.