29 const std::vector<double>& config,
37 const std::vector<double>& config,
38 const moveit::core::RobotModelConstPtr& robot_model)
51 moveit_msgs::Constraints gc;
53 for(
size_t i = 0; i <
joints_.size(); ++i)
55 moveit_msgs::JointConstraint jc;
58 gc.joint_constraints.push_back(jc);
72 state.setToDefaultValues();
76 state.getRobotModel()->getJointModelGroup(
group_name_));
86 moveit_msgs::RobotState robot_state;
87 for (
size_t i = 0; i <
joints_.size(); ++i)
90 robot_state.joint_state.position.push_back(
joints_.at(i));
103 robot_state.setToDefaultValues();
111 moveit_msgs::RobotState rob_state_msg;
113 return rob_state_msg;
123 sensor_msgs::JointState state;
124 for (
size_t i = 0; i <
joints_.size(); ++i)
127 state.position.push_back(
joints_.at(i));
134 const size_t n {obj.
size()};
135 os <<
"JointConfiguration: [";
136 for(
size_t i = 0; i<n; ++i)
sensor_msgs::JointState toSensorMsg() const
moveit_msgs::Constraints toGoalConstraintsWithoutModel() const
std::vector< double > joints_
Joint positions.
moveit::core::RobotModelConstPtr robot_model_
std::function< std::string(const size_t &)> CreateJointNameFunc
double getJoint(const size_t index) const
Class to define a robot configuration in space with the help of joint values.
moveit_msgs::RobotState toMoveitMsgsRobotStateWithoutModel() const
std::ostream & operator<<(std::ostream &, const CartesianConfiguration &)
moveit_msgs::Constraints constructGoalConstraints(const robot_state::RobotState &state, const robot_model::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Class to define robot configuration in space.
CreateJointNameFunc create_joint_name_func_
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::RobotState &robot_state, bool copy_attached_bodies=true)
moveit_msgs::RobotState toMoveitMsgsRobotStateWithModel() const
moveit_msgs::Constraints toGoalConstraintsWithModel() const
robot_state::RobotState toRobotState() const