Public Member Functions | Private Member Functions | Private Attributes | List of all members
pilz_industrial_motion_testutils::JointConfiguration Class Reference

Class to define a robot configuration in space with the help of joint values. More...

#include <jointconfiguration.h>

Inheritance diagram for pilz_industrial_motion_testutils::JointConfiguration:
Inheritance graph
[legend]

Public Member Functions

double getJoint (const size_t index) const
 
const std::vector< double > getJoints () const
 
 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 setCreateJointNameFunc (CreateJointNameFunc create_joint_name_func)
 
void setJoint (const size_t index, const double value)
 
size_t size () const
 
moveit_msgs::Constraints toGoalConstraints () const override
 
moveit_msgs::RobotState toMoveitMsgsRobotState () const override
 
robot_state::RobotState toRobotState () const
 
sensor_msgs::JointState toSensorMsg () const
 
- Public Member Functions inherited from pilz_industrial_motion_testutils::RobotConfiguration
void clearModel ()
 
std::string getGroupName () const
 
 RobotConfiguration ()
 
 RobotConfiguration (const std::string &group_name)
 
 RobotConfiguration (const std::string &group_name, const moveit::core::RobotModelConstPtr &robot_model)
 
void setGroupName (const std::string &group_name)
 
void setRobotModel (moveit::core::RobotModelConstPtr robot_model)
 

Private Member Functions

moveit_msgs::Constraints toGoalConstraintsWithModel () const
 
moveit_msgs::Constraints toGoalConstraintsWithoutModel () const
 
moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel () const
 
moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel () const
 

Private Attributes

CreateJointNameFunc create_joint_name_func_
 
std::vector< double > joints_
 Joint positions. More...
 

Additional Inherited Members

- Protected Attributes inherited from pilz_industrial_motion_testutils::RobotConfiguration
std::string group_name_
 
moveit::core::RobotModelConstPtr robot_model_
 

Detailed Description

Class to define a robot configuration in space with the help of joint values.

Definition at line 48 of file jointconfiguration.h.

Constructor & Destructor Documentation

pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration ( )

Definition at line 24 of file jointconfiguration.cpp.

pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration ( const std::string &  group_name,
const std::vector< double > &  config,
CreateJointNameFunc &&  create_joint_name_func 
)

Definition at line 28 of file jointconfiguration.cpp.

pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration ( const std::string &  group_name,
const std::vector< double > &  config,
const moveit::core::RobotModelConstPtr &  robot_model 
)

Definition at line 36 of file jointconfiguration.cpp.

Member Function Documentation

double pilz_industrial_motion_testutils::JointConfiguration::getJoint ( const size_t  index) const
inline

Definition at line 111 of file jointconfiguration.h.

const std::vector< double > pilz_industrial_motion_testutils::JointConfiguration::getJoints ( ) const
inline

Definition at line 116 of file jointconfiguration.h.

void pilz_industrial_motion_testutils::JointConfiguration::setCreateJointNameFunc ( CreateJointNameFunc  create_joint_name_func)
inline

Definition at line 126 of file jointconfiguration.h.

void pilz_industrial_motion_testutils::JointConfiguration::setJoint ( const size_t  index,
const double  value 
)
inline

Definition at line 106 of file jointconfiguration.h.

size_t pilz_industrial_motion_testutils::JointConfiguration::size ( ) const
inline

Definition at line 121 of file jointconfiguration.h.

moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraints ( ) const
inlineoverridevirtual
moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraintsWithModel ( ) const
private

Definition at line 64 of file jointconfiguration.cpp.

moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraintsWithoutModel ( ) const
private

Definition at line 44 of file jointconfiguration.cpp.

moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotState ( ) const
inlineoverridevirtual
moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotStateWithModel ( ) const
private

Definition at line 108 of file jointconfiguration.cpp.

moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotStateWithoutModel ( ) const
private

Definition at line 79 of file jointconfiguration.cpp.

robot_state::RobotState pilz_industrial_motion_testutils::JointConfiguration::toRobotState ( ) const

Definition at line 95 of file jointconfiguration.cpp.

sensor_msgs::JointState pilz_industrial_motion_testutils::JointConfiguration::toSensorMsg ( ) const

Definition at line 116 of file jointconfiguration.cpp.

Member Data Documentation

CreateJointNameFunc pilz_industrial_motion_testutils::JointConfiguration::create_joint_name_func_
private

Definition at line 89 of file jointconfiguration.h.

std::vector<double> pilz_industrial_motion_testutils::JointConfiguration::joints_
private

Joint positions.

Definition at line 87 of file jointconfiguration.h.


The documentation for this class was generated from the following files:


pilz_industrial_motion_testutils
Author(s):
autogenerated on Mon Apr 6 2020 03:17:28