Go to the documentation of this file.
35 #ifndef JOINTCONFIGURATION_H
36 #define JOINTCONFIGURATION_H
44 #include <sensor_msgs/JointState.h>
52 class JointConfigurationException :
public std::runtime_error
66 class JointConfiguration :
public RobotConfiguration
75 const moveit::core::RobotModelConstPtr& robot_model);
78 void setJoint(
const size_t index,
const double value);
79 double getJoint(
const size_t index)
const;
80 const std::vector<double>
getJoints()
const;
145 #endif // JOINTCONFIGURATION_H
void setCreateJointNameFunc(CreateJointNameFunc create_joint_name_func)
double getJoint(const size_t index) const
JointConfigurationException(const std::string &error_desc)
void setJoint(const size_t index, const double value)
sensor_msgs::JointState toSensorMsg() const
moveit::core::RobotModelConstPtr robot_model_
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
moveit_msgs::Constraints toGoalConstraints() const override
robot_state::RobotState toRobotState() const
moveit_msgs::Constraints toGoalConstraintsWithoutModel() const
std::vector< double > joints_
Joint positions.
Class to define a robot configuration in space with the help of joint values.
std::function< std::string(const size_t &)> CreateJointNameFunc
CreateJointNameFunc create_joint_name_func_
const std::vector< double > getJoints() const
moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel() const
moveit_msgs::Constraints toGoalConstraintsWithModel() const
moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel() const
moveit_msgs::RobotState toMoveitMsgsRobotState() const override