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>
66moveit_msgs::msg::Constraints
mergeConstraints(
const moveit_msgs::msg::Constraints& first,
67 const moveit_msgs::msg::Constraints& second);
85 double tolerance_above);
101 double tolerance = std::numeric_limits<double>::epsilon());
130 const geometry_msgs::msg::PoseStamped& pose,
131 double tolerance_pos = 1e-3,
double tolerance_angle = 1e-2);
149 const geometry_msgs::msg::PoseStamped& pose,
150 const std::vector<double>& tolerance_pos,
151 const std::vector<double>& tolerance_angle);
162bool updatePoseConstraint(moveit_msgs::msg::Constraints& constraints,
const std::string& link_name,
163 const geometry_msgs::msg::PoseStamped& pose);
177 const geometry_msgs::msg::QuaternionStamped& quat,
178 double tolerance = 1e-2);
190 const geometry_msgs::msg::QuaternionStamped& quat);
206 const geometry_msgs::msg::Point& reference_point,
207 const geometry_msgs::msg::PointStamped& goal_point,
208 double tolerance = 1e-3);
223 const geometry_msgs::msg::PointStamped& goal_point,
224 double tolerance = 1e-3);
236 const geometry_msgs::msg::PointStamped& goal_point);
273bool constructConstraints(
const rclcpp::Node::SharedPtr& node,
const std::string& constraints_param,
274 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 updateOrientationConstraint(moveit_msgs::msg::Constraints &constraints, const std::string &link_name, const geometry_msgs::msg::QuaternionStamped &quat)
Update an orientation constraint for one link with a new quaternion.
std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints &constr)
bool updatePositionConstraint(moveit_msgs::msg::Constraints &constraints, const std::string &link_name, const geometry_msgs::msg::PointStamped &goal_point)
Update a position constraint for one link with a new position.
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 updateJointConstraints(moveit_msgs::msg::Constraints &constraints, const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg)
Update joint constraints with a new JointModelGroup state.
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.
bool updatePoseConstraint(moveit_msgs::msg::Constraints &constraints, const std::string &link_name, const geometry_msgs::msg::PoseStamped &pose)
Update a pose constraint for one link with a new pose.
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.