17 #ifndef JOINTCONFIGURATION_H 18 #define JOINTCONFIGURATION_H 25 #include <sensor_msgs/JointState.h> 53 const std::vector<double>&
config,
57 const std::vector<double>& config,
58 const moveit::core::RobotModelConstPtr& robot_model);
61 void setJoint(
const size_t index,
const double value);
62 double getJoint(
const size_t index)
const;
63 const std::vector<double> getJoints()
const;
67 moveit_msgs::Constraints toGoalConstraints()
const override;
68 moveit_msgs::RobotState toMoveitMsgsRobotState()
const override;
70 sensor_msgs::JointState toSensorMsg()
const;
72 robot_state::RobotState toRobotState()
const;
77 moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel()
const;
78 moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel()
const;
80 moveit_msgs::Constraints toGoalConstraintsWithoutModel()
const;
81 moveit_msgs::Constraints toGoalConstraintsWithModel()
const;
94 return robot_model_ ? toGoalConstraintsWithModel() : toGoalConstraintsWithoutModel();
99 return robot_model_ ? toMoveitMsgsRobotStateWithModel() : toMoveitMsgsRobotStateWithoutModel();
104 joints_.at(index) = value;
109 return joints_.at(index);
119 return joints_.size();
124 create_joint_name_func_ = create_joint_name_func;
129 #endif // JOINTCONFIGURATION_H const std::vector< double > getJoints() const
JointConfigurationException(const std::string error_desc)
moveit_msgs::Constraints toGoalConstraints() const override
std::vector< double > joints_
Joint positions.
std::size_t size(custom_string const &s)
std::function< std::string(const size_t &)> CreateJointNameFunc
Class to define a robot configuration in space with the help of joint values.
void setCreateJointNameFunc(CreateJointNameFunc create_joint_name_func)
double getJoint(const size_t index) const
void setJoint(const size_t index, const double value)
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
Class to define robot configuration in space.
moveit_msgs::RobotState toMoveitMsgsRobotState() const override
CreateJointNameFunc create_joint_name_func_