39 #include <moveit_msgs/msg/constraints.hpp>
40 #include <geometry_msgs/msg/point_stamped.hpp>
41 #include <geometry_msgs/msg/pose_stamped.hpp>
42 #include <geometry_msgs/msg/quaternion_stamped.hpp>
66 moveit_msgs::msg::Constraints
mergeConstraints(
const moveit_msgs::msg::Constraints& first,
67 const moveit_msgs::msg::Constraints& second);
70 [[deprecated(
"Use moveit/utils/message_checks.h instead")]]
bool isEmpty(
const moveit_msgs::msg::Constraints& constr);
88 double tolerance_above);
103 double tolerance = std::numeric_limits<double>::epsilon());
121 const geometry_msgs::msg::PoseStamped& pose,
122 double tolerance_pos = 1e-3,
double tolerance_angle = 1e-2);
140 const geometry_msgs::msg::PoseStamped& pose,
141 const std::vector<double>& tolerance_pos,
142 const std::vector<double>& tolerance_angle);
156 const geometry_msgs::msg::QuaternionStamped& quat,
157 double tolerance = 1e-2);
173 const geometry_msgs::msg::Point& reference_point,
174 const geometry_msgs::msg::PointStamped& goal_point,
175 double tolerance = 1e-3);
190 const geometry_msgs::msg::PointStamped& goal_point,
191 double tolerance = 1e-3);
228 bool constructConstraints(
const rclcpp::Node::SharedPtr& node,
const std::string& constraints_param,
229 moveit_msgs::msg::Constraints& constraints);
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Representation and evaluation of kinematic constraints.
bool isEmpty(const moveit_msgs::msg::Constraints &constr)
Check if any constraints were specified.
std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints &constr)
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....
bool resolveConstraintFrames(const moveit::core::RobotState &state, moveit_msgs::msg::Constraints &constraints)
Resolves frames used in constraints to links in the robot model.
bool constructConstraints(const rclcpp::Node::SharedPtr &node, const std::string &constraints_param, moveit_msgs::msg::Constraints &constraints)
extract constraint message from node parameters.
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.