62 CartesianConfiguration(
const std::string& group_name,
const std::string& link_name,
const std::vector<double>& config);
64 CartesianConfiguration(
const std::string& group_name,
const std::string& link_name,
const std::vector<double>& config,
65 const moveit::core::RobotModelConstPtr& robot_model);
74 void setPose(
const geometry_msgs::msg::Pose& pose);
75 const geometry_msgs::msg::Pose&
getPose()
const;
76 geometry_msgs::msg::Pose&
getPose();
90 static geometry_msgs::msg::Pose toPose(
const std::vector<double>& pose);
91 static geometry_msgs::msg::PoseStamped toStampedPose(
const geometry_msgs::msg::Pose& pose);
94 std::string link_name_;
95 geometry_msgs::msg::Pose pose_;
99 std::optional<double> tolerance_pose_;
103 std::optional<double> tolerance_angle_;
106 std::optional<JointConfiguration> seed_;
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....