Class to define a robot configuration in space with the help of joint values.
More...
#include <jointconfiguration.h>
Class to define a robot configuration in space with the help of joint values.
Definition at line 48 of file jointconfiguration.h.
pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration |
( |
| ) |
|
pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration |
( |
const std::string & |
group_name, |
|
|
const std::vector< double > & |
config, |
|
|
CreateJointNameFunc && |
create_joint_name_func |
|
) |
| |
pilz_industrial_motion_testutils::JointConfiguration::JointConfiguration |
( |
const std::string & |
group_name, |
|
|
const std::vector< double > & |
config, |
|
|
const moveit::core::RobotModelConstPtr & |
robot_model |
|
) |
| |
double pilz_industrial_motion_testutils::JointConfiguration::getJoint |
( |
const size_t |
index | ) |
const |
|
inline |
const std::vector< double > pilz_industrial_motion_testutils::JointConfiguration::getJoints |
( |
| ) |
const |
|
inline |
void pilz_industrial_motion_testutils::JointConfiguration::setCreateJointNameFunc |
( |
CreateJointNameFunc |
create_joint_name_func | ) |
|
|
inline |
void pilz_industrial_motion_testutils::JointConfiguration::setJoint |
( |
const size_t |
index, |
|
|
const double |
value |
|
) |
| |
|
inline |
size_t pilz_industrial_motion_testutils::JointConfiguration::size |
( |
| ) |
const |
|
inline |
moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraints |
( |
| ) |
const |
|
inlineoverridevirtual |
moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraintsWithModel |
( |
| ) |
const |
|
private |
moveit_msgs::Constraints pilz_industrial_motion_testutils::JointConfiguration::toGoalConstraintsWithoutModel |
( |
| ) |
const |
|
private |
moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotState |
( |
| ) |
const |
|
inlineoverridevirtual |
moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotStateWithModel |
( |
| ) |
const |
|
private |
moveit_msgs::RobotState pilz_industrial_motion_testutils::JointConfiguration::toMoveitMsgsRobotStateWithoutModel |
( |
| ) |
const |
|
private |
robot_state::RobotState pilz_industrial_motion_testutils::JointConfiguration::toRobotState |
( |
| ) |
const |
sensor_msgs::JointState pilz_industrial_motion_testutils::JointConfiguration::toSensorMsg |
( |
| ) |
const |
CreateJointNameFunc pilz_industrial_motion_testutils::JointConfiguration::create_joint_name_func_ |
|
private |
std::vector<double> pilz_industrial_motion_testutils::JointConfiguration::joints_ |
|
private |
The documentation for this class was generated from the following files: