43 #include <sensor_msgs/msg/joint_state.hpp> 
   74                      const moveit::core::RobotModelConstPtr& robot_model);
 
   77   void setJoint(
const size_t index, 
const double value);
 
   78   double getJoint(
const size_t index) 
const;
 
   79   const std::vector<double> 
getJoints() 
const;
 
   93   moveit_msgs::msg::RobotState toMoveitMsgsRobotStateWithoutModel() 
const;
 
   94   moveit_msgs::msg::RobotState toMoveitMsgsRobotStateWithModel() 
const;
 
   96   moveit_msgs::msg::Constraints toGoalConstraintsWithoutModel() 
const;
 
   97   moveit_msgs::msg::Constraints toGoalConstraintsWithModel() 
const;
 
  101   std::vector<double> joints_;
 
  110   return robot_model_ ? toGoalConstraintsWithModel() : toGoalConstraintsWithoutModel();
 
  115   return robot_model_ ? toMoveitMsgsRobotStateWithModel() : toMoveitMsgsRobotStateWithoutModel();
 
  120   joints_.at(index) = value;
 
  125   return joints_.at(index);
 
  135   return joints_.size();
 
  140   create_joint_name_func_ = std::move(create_joint_name_func);
 
Representation of a robot's state. This includes position, velocity, acceleration and effort.
 
JointConfigurationException(const std::string &error_desc)
 
Class to define a robot configuration in space with the help of joint values.
 
const std::vector< double > getJoints() const
 
sensor_msgs::msg::JointState toSensorMsg() const
 
moveit_msgs::msg::Constraints toGoalConstraints() const override
 
void setJoint(const size_t index, const double value)
 
moveit_msgs::msg::RobotState toMoveitMsgsRobotState() const override
 
double getJoint(const size_t index) const
 
moveit::core::RobotState toRobotState() const
 
void setCreateJointNameFunc(CreateJointNameFunc create_joint_name_func)
 
Class to define robot configuration in space.
 
moveit::core::RobotModelConstPtr robot_model_
 
std::function< std::string(const size_t &)> CreateJointNameFunc
 
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)