47 :
RobotConfiguration(group_name), joints_(config), create_joint_name_func_(create_joint_name_func)
52 const moveit::core::RobotModelConstPtr& robot_model)
57moveit_msgs::msg::Constraints JointConfiguration::toGoalConstraintsWithoutModel()
const
59 if (!create_joint_name_func_)
64 moveit_msgs::msg::Constraints gc;
66 for (
size_t i = 0; i < joints_.size(); ++i)
68 moveit_msgs::msg::JointConstraint jc;
69 jc.joint_name = create_joint_name_func_(i);
70 jc.position = joints_.at(i);
71 gc.joint_constraints.push_back(jc);
77moveit_msgs::msg::Constraints JointConfiguration::toGoalConstraintsWithModel()
const
81 throw JointConfigurationException(
"No robot model set");
85 state.setToDefaultValues();
91moveit_msgs::msg::RobotState JointConfiguration::toMoveitMsgsRobotStateWithoutModel()
const
93 if (!create_joint_name_func_)
95 throw JointConfigurationException(
"Create-Joint-Name function not set");
98 moveit_msgs::msg::RobotState robot_state;
99 for (
size_t i = 0; i < joints_.size(); ++i)
101 robot_state.joint_state.name.emplace_back(create_joint_name_func_(i));
102 robot_state.joint_state.position.push_back(joints_.at(i));
120moveit_msgs::msg::RobotState JointConfiguration::toMoveitMsgsRobotStateWithModel()
const
123 moveit_msgs::msg::RobotState rob_state_msg;
125 return rob_state_msg;
130 if (!create_joint_name_func_)
135 sensor_msgs::msg::JointState state;
136 for (
size_t i = 0; i < joints_.size(); ++i)
138 state.name.emplace_back(create_joint_name_func_(i));
139 state.position.push_back(joints_.at(i));
146 const size_t n{ obj.
size() };
147 os <<
"JointConfiguration: [";
148 for (
size_t i = 0; i < n; ++i)
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Class to define a robot configuration in space with the help of joint values.
sensor_msgs::msg::JointState toSensorMsg() const
double getJoint(const size_t index) const
moveit::core::RobotState toRobotState() const
Class to define robot configuration in space.
moveit::core::RobotModelConstPtr robot_model_
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::function< std::string(const size_t &)> CreateJointNameFunc
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)