47 : RobotConfiguration(group_name), joints_(
config), create_joint_name_func_(create_joint_name_func)
52 const moveit::core::RobotModelConstPtr& robot_model)
53 : RobotConfiguration(group_name, robot_model), joints_(
config)
61 throw JointConfigurationException(
"Create-Joint-Name function not set");
64 moveit_msgs::Constraints gc;
66 for (
size_t i = 0; i <
joints_.size(); ++i)
68 moveit_msgs::JointConstraint jc;
71 gc.joint_constraints.push_back(jc);
85 state.setToDefaultValues();
98 moveit_msgs::RobotState robot_state;
99 for (
size_t i = 0; i <
joints_.size(); ++i)
102 robot_state.joint_state.position.push_back(
joints_.at(i));
115 robot_state.setToDefaultValues();
123 moveit_msgs::RobotState rob_state_msg;
125 return rob_state_msg;
135 sensor_msgs::JointState state;
136 for (
size_t i = 0; i <
joints_.size(); ++i)
144 std::ostream&
operator<<(std::ostream& os,
const JointConfiguration& obj)
146 const size_t n{
obj.size() };
147 os <<
"JointConfiguration: [";
148 for (
size_t i = 0; i < n; ++i)
150 os <<
obj.getJoint(i);