37 #include <geometric_shapes/solid_primitive_dims.h>
40 #include <rclcpp/logger.hpp>
41 #include <rclcpp/logging.hpp>
42 #include <rclcpp/node.hpp>
43 #include <rclcpp/parameter_value.hpp>
45 #include <rclcpp/node.hpp>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
47 #include <tf2_eigen/tf2_eigen.hpp>
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_kinematic_constraints.utils");
56 moveit_msgs::msg::Constraints
mergeConstraints(
const moveit_msgs::msg::Constraints& first,
57 const moveit_msgs::msg::Constraints& second)
59 moveit_msgs::msg::Constraints
r;
63 for (
const moveit_msgs::msg::JointConstraint& jc_first : first.joint_constraints)
66 for (
const moveit_msgs::msg::JointConstraint& jc_second : second.joint_constraints)
67 if (jc_second.joint_name == jc_first.joint_name)
71 moveit_msgs::msg::JointConstraint m;
72 const moveit_msgs::msg::JointConstraint&
a = jc_first;
73 const moveit_msgs::msg::JointConstraint& b = jc_second;
74 double low = std::max(
a.position -
a.tolerance_below, b.position - b.tolerance_below);
75 double high = std::min(
a.position +
a.tolerance_above, b.position + b.tolerance_above);
78 RCLCPP_ERROR(LOGGER,
"Attempted to merge incompatible constraints for joint '%s'. Discarding constraint.",
79 a.joint_name.c_str());
83 m.joint_name =
a.joint_name;
85 std::max(low, std::min((
a.position *
a.weight + b.position * b.weight) / (
a.weight + b.weight), high));
86 m.weight = (
a.weight + b.weight) / 2.0;
87 m.tolerance_above = std::max(0.0, high - m.position);
88 m.tolerance_below = std::max(0.0, m.position - low);
89 r.joint_constraints.push_back(m);
94 r.joint_constraints.push_back(jc_first);
98 for (
const moveit_msgs::msg::JointConstraint& jc_second : second.joint_constraints)
101 for (
const moveit_msgs::msg::JointConstraint& jc_first : first.joint_constraints)
102 if (jc_second.joint_name == jc_first.joint_name)
108 r.joint_constraints.push_back(jc_second);
112 r.position_constraints = first.position_constraints;
113 for (
const moveit_msgs::msg::PositionConstraint& position_constraint : second.position_constraints)
114 r.position_constraints.push_back(position_constraint);
116 r.orientation_constraints = first.orientation_constraints;
117 for (
const moveit_msgs::msg::OrientationConstraint& orientation_constraint : second.orientation_constraints)
118 r.orientation_constraints.push_back(orientation_constraint);
120 r.visibility_constraints = first.visibility_constraints;
121 for (
const moveit_msgs::msg::VisibilityConstraint& visibility_constraint : second.visibility_constraints)
122 r.visibility_constraints.push_back(visibility_constraint);
127 bool isEmpty(
const moveit_msgs::msg::Constraints& constr)
134 return constr.position_constraints.size() + constr.orientation_constraints.size() +
135 constr.visibility_constraints.size() + constr.joint_constraints.size();
146 double tolerance_above)
148 moveit_msgs::msg::Constraints goal;
149 std::vector<double> vals;
151 goal.joint_constraints.resize(vals.size());
152 for (std::size_t i = 0; i < vals.size(); ++i)
155 goal.joint_constraints[i].position = vals[i];
156 goal.joint_constraints[i].tolerance_above = tolerance_above;
157 goal.joint_constraints[i].tolerance_below = tolerance_below;
158 goal.joint_constraints[i].weight = 1.0;
165 const geometry_msgs::msg::PoseStamped& pose,
166 double tolerance_pos,
double tolerance_angle)
168 moveit_msgs::msg::Constraints goal;
170 goal.position_constraints.resize(1);
171 moveit_msgs::msg::PositionConstraint& pcm = goal.position_constraints[0];
172 pcm.link_name = link_name;
173 pcm.target_point_offset.x = 0;
174 pcm.target_point_offset.y = 0;
175 pcm.target_point_offset.z = 0;
176 pcm.constraint_region.primitives.resize(1);
177 shape_msgs::msg::SolidPrimitive& bv = pcm.constraint_region.primitives[0];
178 bv.type = shape_msgs::msg::SolidPrimitive::SPHERE;
179 bv.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::msg::SolidPrimitive::SPHERE>());
180 bv.dimensions[shape_msgs::msg::SolidPrimitive::SPHERE_RADIUS] = tolerance_pos;
182 pcm.header = pose.header;
183 pcm.constraint_region.primitive_poses.resize(1);
184 pcm.constraint_region.primitive_poses[0].position = pose.pose.position;
187 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
188 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
189 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
190 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
193 goal.orientation_constraints.resize(1);
194 moveit_msgs::msg::OrientationConstraint& ocm = goal.orientation_constraints[0];
195 ocm.link_name = link_name;
196 ocm.header = pose.header;
197 ocm.orientation = pose.pose.orientation;
198 ocm.absolute_x_axis_tolerance = tolerance_angle;
199 ocm.absolute_y_axis_tolerance = tolerance_angle;
200 ocm.absolute_z_axis_tolerance = tolerance_angle;
207 const geometry_msgs::msg::PoseStamped& pose,
208 const std::vector<double>& tolerance_pos,
209 const std::vector<double>& tolerance_angle)
212 if (tolerance_pos.size() == 3)
214 shape_msgs::msg::SolidPrimitive& bv = goal.position_constraints[0].constraint_region.primitives[0];
215 bv.type = shape_msgs::msg::SolidPrimitive::BOX;
216 bv.dimensions.resize(geometric_shapes::solidPrimitiveDimCount<shape_msgs::msg::SolidPrimitive::BOX>());
217 bv.dimensions[shape_msgs::msg::SolidPrimitive::BOX_X] = tolerance_pos[0];
218 bv.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Y] = tolerance_pos[1];
219 bv.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Z] = tolerance_pos[2];
221 if (tolerance_angle.size() == 3)
223 moveit_msgs::msg::OrientationConstraint& ocm = goal.orientation_constraints[0];
224 ocm.absolute_x_axis_tolerance = tolerance_angle[0];
225 ocm.absolute_y_axis_tolerance = tolerance_angle[1];
226 ocm.absolute_z_axis_tolerance = tolerance_angle[2];
232 const geometry_msgs::msg::QuaternionStamped& quat,
235 moveit_msgs::msg::Constraints goal;
236 goal.orientation_constraints.resize(1);
237 moveit_msgs::msg::OrientationConstraint& ocm = goal.orientation_constraints[0];
238 ocm.link_name = link_name;
239 ocm.header = quat.header;
240 ocm.orientation = quat.quaternion;
241 ocm.absolute_x_axis_tolerance = tolerance;
242 ocm.absolute_y_axis_tolerance = tolerance;
243 ocm.absolute_z_axis_tolerance = tolerance;
249 const geometry_msgs::msg::PointStamped& goal_point,
252 geometry_msgs::msg::Point
p;
260 const geometry_msgs::msg::Point& reference_point,
261 const geometry_msgs::msg::PointStamped& goal_point,
264 moveit_msgs::msg::Constraints goal;
265 goal.position_constraints.resize(1);
266 moveit_msgs::msg::PositionConstraint& pcm = goal.position_constraints[0];
267 pcm.link_name = link_name;
268 pcm.target_point_offset.x = reference_point.x;
269 pcm.target_point_offset.y = reference_point.y;
270 pcm.target_point_offset.z = reference_point.z;
271 pcm.constraint_region.primitives.resize(1);
272 pcm.constraint_region.primitives[0].type = shape_msgs::msg::SolidPrimitive::SPHERE;
273 pcm.constraint_region.primitives[0].dimensions.resize(
274 geometric_shapes::solidPrimitiveDimCount<shape_msgs::msg::SolidPrimitive::SPHERE>());
275 pcm.constraint_region.primitives[0].dimensions[shape_msgs::msg::SolidPrimitive::SPHERE_RADIUS] = tolerance;
277 pcm.header = goal_point.header;
278 pcm.constraint_region.primitive_poses.resize(1);
279 pcm.constraint_region.primitive_poses[0].position = goal_point.point;
282 pcm.constraint_region.primitive_poses[0].orientation.x = 0.0;
283 pcm.constraint_region.primitive_poses[0].orientation.y = 0.0;
284 pcm.constraint_region.primitive_poses[0].orientation.z = 0.0;
285 pcm.constraint_region.primitive_poses[0].orientation.w = 1.0;
292 static bool constructPoseStamped(
const rclcpp::Node::SharedPtr& node,
const std::string& pose_param,
293 geometry_msgs::msg::PoseStamped& pose)
295 if (!node->get_parameter(pose_param +
".frame_id", pose.header.frame_id))
298 std::vector<double> orientation;
299 if (!node->get_parameter(pose_param +
".orientation", orientation) || orientation.size() != 3)
303 q.setRPY(orientation[0], orientation[1], orientation[2]);
304 pose.pose.orientation = toMsg(q);
306 std::vector<double> position;
307 if (!node->get_parameter(pose_param +
".position", position) || position.size() != 3)
310 pose.pose.position.x = position[0];
311 pose.pose.position.y = position[1];
312 pose.pose.position.z = position[2];
318 static bool constructConstraint(
const rclcpp::Node::SharedPtr& node,
const std::string& constraint_param,
319 moveit_msgs::msg::JointConstraint& constraint)
321 node->get_parameter(constraint_param +
".weight", constraint.weight);
322 node->get_parameter(constraint_param +
".joint_name", constraint.joint_name);
323 node->get_parameter(constraint_param +
".position", constraint.position);
326 if (node->get_parameter(constraint_param +
".tolerance", tolerance))
328 constraint.tolerance_below = tolerance;
329 constraint.tolerance_above = tolerance;
331 else if (node->has_parameter(constraint_param +
".tolerances"))
333 std::vector<double> tolerances;
334 node->get_parameter(constraint_param +
".tolerances", tolerances);
335 if (tolerances.size() != 2)
338 constraint.tolerance_below = tolerances[0];
339 constraint.tolerance_above = tolerances[1];
341 else if (node->has_parameter(constraint_param +
".bounds"))
343 std::vector<double> bounds;
344 node->get_parameter(constraint_param +
".bounds", bounds);
345 if (bounds.size() != 2)
348 const double lower_bound = bounds[0];
349 const double upper_bound = bounds[1];
351 constraint.position = (lower_bound + upper_bound) / 2;
352 constraint.tolerance_below = constraint.position - lower_bound;
353 constraint.tolerance_above = upper_bound - constraint.position;
360 static bool constructConstraint(
const rclcpp::Node::SharedPtr& node,
const std::string& constraint_param,
361 moveit_msgs::msg::PositionConstraint& constraint)
363 node->get_parameter(constraint_param +
".frame_id", constraint.header.frame_id);
364 node->get_parameter(constraint_param +
".weight", constraint.weight);
365 node->get_parameter(constraint_param +
".link_name", constraint.link_name);
367 std::vector<double> target_offset;
368 if (node->get_parameter(constraint_param +
".target_offset", target_offset))
370 if (target_offset.size() != 3)
373 constraint.target_point_offset.x = target_offset[0];
374 constraint.target_point_offset.y = target_offset[1];
375 constraint.target_point_offset.z = target_offset[2];
377 if (!node->list_parameters({ constraint_param +
".region" }, 1).names.empty())
379 geometry_msgs::msg::Pose region_pose;
380 region_pose.orientation.w = 1.0;
382 shape_msgs::msg::SolidPrimitive region_primitive;
383 region_primitive.type = shape_msgs::msg::SolidPrimitive::BOX;
384 region_primitive.dimensions.resize(3);
386 const auto parse_dimension = [&](
const std::string& dimension_param,
double& center,
double& dimension) ->
bool {
387 std::vector<double> dimension_limits;
388 if (!node->get_parameter(constraint_param +
".region." + dimension_param, dimension_limits) ||
389 dimension_limits.size() != 2)
392 center = (dimension_limits[0] + dimension_limits[1]) / 2;
393 dimension = dimension_limits[1] - dimension_limits[2];
397 if (!parse_dimension(
"x", region_pose.position.x,
398 region_primitive.dimensions[shape_msgs::msg::SolidPrimitive::BOX_X]) ||
399 !parse_dimension(
"y", region_pose.position.y,
400 region_primitive.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Y]) ||
401 !parse_dimension(
"z", region_pose.position.z,
402 region_primitive.dimensions[shape_msgs::msg::SolidPrimitive::BOX_Z]))
405 constraint.constraint_region.primitive_poses.push_back(region_pose);
406 constraint.constraint_region.primitives.emplace_back(region_primitive);
413 static bool constructConstraint(
const rclcpp::Node::SharedPtr& node,
const std::string& constraint_param,
414 moveit_msgs::msg::OrientationConstraint& constraint)
416 node->get_parameter(constraint_param +
".frame_id", constraint.header.frame_id);
417 node->get_parameter(constraint_param +
".weight", constraint.weight);
418 node->get_parameter(constraint_param +
".link_name", constraint.link_name);
420 std::vector<double> orientation;
421 if (node->get_parameter(constraint_param +
".orientation", orientation))
423 if (orientation.size() != 3)
427 q.setRPY(orientation[0], orientation[1], orientation[2]);
428 constraint.orientation = toMsg(q);
431 std::vector<double> tolerances;
432 if (node->get_parameter(constraint_param +
".tolerances", tolerances))
434 if (tolerances.size() != 3)
437 constraint.absolute_x_axis_tolerance = tolerances[0];
438 constraint.absolute_y_axis_tolerance = tolerances[1];
439 constraint.absolute_z_axis_tolerance = tolerances[2];
446 static bool constructConstraint(
const rclcpp::Node::SharedPtr& node,
const std::string& constraint_param,
447 moveit_msgs::msg::VisibilityConstraint& constraint)
449 node->get_parameter(constraint_param +
".weight", constraint.weight);
450 node->get_parameter(constraint_param +
".target_radius", constraint.target_radius);
451 node->get_parameter(constraint_param +
".cone_sides", constraint.cone_sides);
452 node->get_parameter(constraint_param +
".max_view_angle", constraint.max_view_angle);
453 node->get_parameter(constraint_param +
".max_range_angle", constraint.max_range_angle);
456 if (!node->list_parameters({ constraint_param +
".target_pose" }, 1).names.empty())
458 if (!constructPoseStamped(node, constraint_param +
".target_pose", constraint.target_pose))
462 if (!node->list_parameters({ constraint_param +
".sensor_pose" }, 1).names.empty())
464 if (!constructPoseStamped(node, constraint_param +
".sensor_pose", constraint.sensor_pose))
468 constraint.sensor_view_direction = moveit_msgs::msg::VisibilityConstraint::SENSOR_X;
474 static bool collectConstraints(
const rclcpp::Node::SharedPtr& node,
const std::vector<std::string>& constraint_ids,
475 moveit_msgs::msg::Constraints& constraints)
477 for (
const auto& constraint_id : constraint_ids)
479 const auto constraint_param =
"constraints." + constraint_id;
480 if (!node->has_parameter(constraint_param +
".type"))
482 RCLCPP_ERROR(LOGGER,
"constraint parameter \"%s\" does not specify its type", constraint_param.c_str());
485 std::string constraint_type;
486 node->get_parameter(constraint_param +
".type", constraint_type);
487 if (constraint_type ==
"joint")
489 constraints.joint_constraints.emplace_back();
490 if (!constructConstraint(node, constraint_param, constraints.joint_constraints.back()))
493 else if (constraint_type ==
"position")
495 constraints.position_constraints.emplace_back();
496 if (!constructConstraint(node, constraint_param, constraints.position_constraints.back()))
499 else if (constraint_type ==
"orientation")
501 constraints.orientation_constraints.emplace_back();
502 if (!constructConstraint(node, constraint_param, constraints.orientation_constraints.back()))
505 else if (constraint_type ==
"visibility")
507 constraints.visibility_constraints.emplace_back();
508 if (!constructConstraint(node, constraint_param, constraints.visibility_constraints.back()))
513 RCLCPP_ERROR_STREAM(LOGGER,
"Unable to process unknown constraint type: " << constraint_type);
522 moveit_msgs::msg::Constraints& constraints)
524 if (!node->get_parameter(constraints_param +
".name", constraints.name))
527 std::vector<std::string> constraint_ids;
528 if (!node->get_parameter(constraints_param +
".constraint_ids", constraint_ids))
531 for (
auto& constraint_id : constraint_ids)
532 constraint_id.insert(0, constraints_param + std::string(
"."));
534 return collectConstraints(node, constraint_ids, constraints);
539 moveit_msgs::msg::Constraints& constraints)
541 for (
auto&
c : constraints.position_constraints)
545 const Eigen::Isometry3d& transform = state.
getFrameInfo(
c.link_name, robot_link, frame_found);
551 if (
c.link_name != robot_link->
getName())
553 Eigen::Isometry3d robot_link_to_link_name = state.
getGlobalLinkTransform(robot_link).inverse() * transform;
554 Eigen::Vector3d offset_link_name(
c.target_point_offset.x,
c.target_point_offset.y,
c.target_point_offset.z);
555 Eigen::Vector3d offset_robot_link = robot_link_to_link_name * offset_link_name;
557 c.link_name = robot_link->
getName();
558 tf2::toMsg(offset_robot_link,
c.target_point_offset);
562 for (
auto&
c : constraints.orientation_constraints)
567 const Eigen::Isometry3d& transform = state.
getFrameInfo(
c.link_name, robot_link, frame_found);
573 if (
c.link_name != robot_link->
getName())
575 c.link_name = robot_link->
getName();
576 Eigen::Quaterniond link_name_to_robot_link(transform.linear().transpose() *
578 Eigen::Quaterniond quat_target;
579 tf2::fromMsg(
c.orientation, quat_target);
580 c.orientation = tf2::toMsg(quat_target * link_name_to_robot_link);
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
A link from the robot. Contains the constant transform applied to the link and its geometry.
const std::string & getName() const
The name of this link.
Representation of a robot's state. This includes position, velocity, acceleration and effort.
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
const Eigen::Isometry3d & getFrameInfo(const std::string &frame_id, const LinkModel *&robot_link, bool &frame_found) const
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
Vec3fX< details::Vec3Data< double > > Vector3d
Representation and evaluation of kinematic constraints.
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.
Core components of MoveIt.
bool isEmpty(const moveit_msgs::msg::PlanningScene &msg)
Check if a message includes any information about a planning scene, or whether it is empty.