moveit2
The MoveIt Motion Planning Framework for ROS 2.
utils.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2011, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
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>
44 
45 #include <rclcpp/node.hpp>
46 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
47 #include <tf2_eigen/tf2_eigen.hpp>
48 
49 using namespace moveit::core;
50 
51 namespace kinematic_constraints
52 {
53 // Logger
54 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit_kinematic_constraints.utils");
55 
56 moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints& first,
57  const moveit_msgs::msg::Constraints& second)
58 {
59  moveit_msgs::msg::Constraints r;
60 
61  // add all joint constraints that are in first but not in second
62  // and merge joint constraints that are for the same joint
63  for (const moveit_msgs::msg::JointConstraint& jc_first : first.joint_constraints)
64  {
65  bool add = true;
66  for (const moveit_msgs::msg::JointConstraint& jc_second : second.joint_constraints)
67  if (jc_second.joint_name == jc_first.joint_name)
68  {
69  add = false;
70  // now we merge
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);
76  if (low > high)
77  {
78  RCLCPP_ERROR(LOGGER, "Attempted to merge incompatible constraints for joint '%s'. Discarding constraint.",
79  a.joint_name.c_str());
80  }
81  else
82  {
83  m.joint_name = a.joint_name;
84  m.position =
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);
90  }
91  break;
92  }
93  if (add)
94  r.joint_constraints.push_back(jc_first);
95  }
96 
97  // add all joint constraints that are in second but not in first
98  for (const moveit_msgs::msg::JointConstraint& jc_second : second.joint_constraints)
99  {
100  bool add = true;
101  for (const moveit_msgs::msg::JointConstraint& jc_first : first.joint_constraints)
102  if (jc_second.joint_name == jc_first.joint_name)
103  {
104  add = false;
105  break;
106  }
107  if (add)
108  r.joint_constraints.push_back(jc_second);
109  }
110 
111  // merge rest of constraints
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);
115 
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);
119 
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);
123 
124  return r;
125 }
126 
127 bool isEmpty(const moveit_msgs::msg::Constraints& constr)
128 {
129  return moveit::core::isEmpty(constr);
130 }
131 
132 std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints& constr)
133 {
134  return constr.position_constraints.size() + constr.orientation_constraints.size() +
135  constr.visibility_constraints.size() + constr.joint_constraints.size();
136 }
137 
138 moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
139  const moveit::core::JointModelGroup* jmg, double tolerance)
140 {
141  return constructGoalConstraints(state, jmg, tolerance, tolerance);
142 }
143 
144 moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState& state,
145  const moveit::core::JointModelGroup* jmg, double tolerance_below,
146  double tolerance_above)
147 {
148  moveit_msgs::msg::Constraints goal;
149  std::vector<double> vals;
150  state.copyJointGroupPositions(jmg, vals);
151  goal.joint_constraints.resize(vals.size());
152  for (std::size_t i = 0; i < vals.size(); ++i)
153  {
154  goal.joint_constraints[i].joint_name = jmg->getVariableNames()[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;
159  }
160 
161  return goal;
162 }
163 
164 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
165  const geometry_msgs::msg::PoseStamped& pose,
166  double tolerance_pos, double tolerance_angle)
167 {
168  moveit_msgs::msg::Constraints goal;
169 
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;
181 
182  pcm.header = pose.header;
183  pcm.constraint_region.primitive_poses.resize(1);
184  pcm.constraint_region.primitive_poses[0].position = pose.pose.position;
185 
186  // orientation of constraint region does not affect anything, since it is a sphere
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;
191  pcm.weight = 1.0;
192 
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;
201  ocm.weight = 1.0;
202 
203  return goal;
204 }
205 
206 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
207  const geometry_msgs::msg::PoseStamped& pose,
208  const std::vector<double>& tolerance_pos,
209  const std::vector<double>& tolerance_angle)
210 {
211  moveit_msgs::msg::Constraints goal = constructGoalConstraints(link_name, pose);
212  if (tolerance_pos.size() == 3)
213  {
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];
220  }
221  if (tolerance_angle.size() == 3)
222  {
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];
227  }
228  return goal;
229 }
230 
231 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
232  const geometry_msgs::msg::QuaternionStamped& quat,
233  double tolerance)
234 {
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;
244  ocm.weight = 1.0;
245  return goal;
246 }
247 
248 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
249  const geometry_msgs::msg::PointStamped& goal_point,
250  double tolerance)
251 {
252  geometry_msgs::msg::Point p;
253  p.x = 0;
254  p.y = 0;
255  p.z = 0;
256  return constructGoalConstraints(link_name, p, goal_point, tolerance);
257 }
258 
259 moveit_msgs::msg::Constraints constructGoalConstraints(const std::string& link_name,
260  const geometry_msgs::msg::Point& reference_point,
261  const geometry_msgs::msg::PointStamped& goal_point,
262  double tolerance)
263 {
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;
276 
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;
280 
281  // orientation of constraint region does not affect anything, since it is a sphere
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;
286  pcm.weight = 1.0;
287 
288  return goal;
289 }
290 
291 // Initialize a PoseStamped message from node parameters specified at pose_param.
292 static bool constructPoseStamped(const rclcpp::Node::SharedPtr& node, const std::string& pose_param,
293  geometry_msgs::msg::PoseStamped& pose)
294 {
295  if (!node->get_parameter(pose_param + ".frame_id", pose.header.frame_id))
296  return false;
297 
298  std::vector<double> orientation;
299  if (!node->get_parameter(pose_param + ".orientation", orientation) || orientation.size() != 3)
300  return false;
301 
302  tf2::Quaternion q;
303  q.setRPY(orientation[0], orientation[1], orientation[2]);
304  pose.pose.orientation = toMsg(q);
305 
306  std::vector<double> position;
307  if (!node->get_parameter(pose_param + ".position", position) || position.size() != 3)
308  return false;
309 
310  pose.pose.position.x = position[0];
311  pose.pose.position.y = position[1];
312  pose.pose.position.z = position[2];
313 
314  return true;
315 }
316 
317 // Initialize a JointConstraint message from node parameters specified at constraint_param.
318 static bool constructConstraint(const rclcpp::Node::SharedPtr& node, const std::string& constraint_param,
319  moveit_msgs::msg::JointConstraint& constraint)
320 {
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);
324 
325  double tolerance;
326  if (node->get_parameter(constraint_param + ".tolerance", tolerance))
327  {
328  constraint.tolerance_below = tolerance;
329  constraint.tolerance_above = tolerance;
330  }
331  else if (node->has_parameter(constraint_param + ".tolerances"))
332  {
333  std::vector<double> tolerances;
334  node->get_parameter(constraint_param + ".tolerances", tolerances);
335  if (tolerances.size() != 2)
336  return false;
337 
338  constraint.tolerance_below = tolerances[0];
339  constraint.tolerance_above = tolerances[1];
340  }
341  else if (node->has_parameter(constraint_param + ".bounds"))
342  {
343  std::vector<double> bounds;
344  node->get_parameter(constraint_param + ".bounds", bounds);
345  if (bounds.size() != 2)
346  return false;
347 
348  const double lower_bound = bounds[0];
349  const double upper_bound = bounds[1];
350 
351  constraint.position = (lower_bound + upper_bound) / 2;
352  constraint.tolerance_below = constraint.position - lower_bound;
353  constraint.tolerance_above = upper_bound - constraint.position;
354  }
355 
356  return true;
357 }
358 
359 // Initialize a PositionConstraint message from node parameters specified at constraint_param.
360 static bool constructConstraint(const rclcpp::Node::SharedPtr& node, const std::string& constraint_param,
361  moveit_msgs::msg::PositionConstraint& constraint)
362 {
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);
366 
367  std::vector<double> target_offset;
368  if (node->get_parameter(constraint_param + ".target_offset", target_offset))
369  {
370  if (target_offset.size() != 3)
371  return false;
372 
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];
376  }
377  if (!node->list_parameters({ constraint_param + ".region" }, 1).names.empty()) // TODO(henningkayser): specify depth
378  {
379  geometry_msgs::msg::Pose region_pose;
380  region_pose.orientation.w = 1.0;
381 
382  shape_msgs::msg::SolidPrimitive region_primitive;
383  region_primitive.type = shape_msgs::msg::SolidPrimitive::BOX;
384  region_primitive.dimensions.resize(3);
385 
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)
390  return false;
391 
392  center = (dimension_limits[0] + dimension_limits[1]) / 2;
393  dimension = dimension_limits[1] - dimension_limits[2];
394  return true;
395  };
396 
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]))
403  return false;
404 
405  constraint.constraint_region.primitive_poses.push_back(region_pose);
406  constraint.constraint_region.primitives.emplace_back(region_primitive);
407  }
408 
409  return true;
410 }
411 
412 // Initialize an OrientationConstraint message from node parameters specified at constraint_param.
413 static bool constructConstraint(const rclcpp::Node::SharedPtr& node, const std::string& constraint_param,
414  moveit_msgs::msg::OrientationConstraint& constraint)
415 {
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);
419 
420  std::vector<double> orientation;
421  if (node->get_parameter(constraint_param + ".orientation", orientation))
422  {
423  if (orientation.size() != 3)
424  return false;
425 
426  tf2::Quaternion q;
427  q.setRPY(orientation[0], orientation[1], orientation[2]);
428  constraint.orientation = toMsg(q);
429  }
430 
431  std::vector<double> tolerances;
432  if (node->get_parameter(constraint_param + ".tolerances", tolerances))
433  {
434  if (tolerances.size() != 3)
435  return false;
436 
437  constraint.absolute_x_axis_tolerance = tolerances[0];
438  constraint.absolute_y_axis_tolerance = tolerances[1];
439  constraint.absolute_z_axis_tolerance = tolerances[2];
440  }
441 
442  return true;
443 }
444 
445 // Initialize a VisibilityConstraint message from node parameters specified at constraint_param.
446 static bool constructConstraint(const rclcpp::Node::SharedPtr& node, const std::string& constraint_param,
447  moveit_msgs::msg::VisibilityConstraint& constraint)
448 {
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);
454 
455  // TODO(henningkayser): specify depth
456  if (!node->list_parameters({ constraint_param + ".target_pose" }, 1).names.empty())
457  {
458  if (!constructPoseStamped(node, constraint_param + ".target_pose", constraint.target_pose))
459  return false;
460  }
461  // TODO(henningkayser): specify depth
462  if (!node->list_parameters({ constraint_param + ".sensor_pose" }, 1).names.empty())
463  {
464  if (!constructPoseStamped(node, constraint_param + ".sensor_pose", constraint.sensor_pose))
465  return false;
466  }
467 
468  constraint.sensor_view_direction = moveit_msgs::msg::VisibilityConstraint::SENSOR_X;
469 
470  return true;
471 }
472 
473 // Initialize a Constraints message containing constraints specified by node parameters under constraint_ids.
474 static bool collectConstraints(const rclcpp::Node::SharedPtr& node, const std::vector<std::string>& constraint_ids,
475  moveit_msgs::msg::Constraints& constraints)
476 {
477  for (const auto& constraint_id : constraint_ids)
478  {
479  const auto constraint_param = "constraints." + constraint_id;
480  if (!node->has_parameter(constraint_param + ".type"))
481  {
482  RCLCPP_ERROR(LOGGER, "constraint parameter \"%s\" does not specify its type", constraint_param.c_str());
483  return false;
484  }
485  std::string constraint_type;
486  node->get_parameter(constraint_param + ".type", constraint_type);
487  if (constraint_type == "joint")
488  {
489  constraints.joint_constraints.emplace_back();
490  if (!constructConstraint(node, constraint_param, constraints.joint_constraints.back()))
491  return false;
492  }
493  else if (constraint_type == "position")
494  {
495  constraints.position_constraints.emplace_back();
496  if (!constructConstraint(node, constraint_param, constraints.position_constraints.back()))
497  return false;
498  }
499  else if (constraint_type == "orientation")
500  {
501  constraints.orientation_constraints.emplace_back();
502  if (!constructConstraint(node, constraint_param, constraints.orientation_constraints.back()))
503  return false;
504  }
505  else if (constraint_type == "visibility")
506  {
507  constraints.visibility_constraints.emplace_back();
508  if (!constructConstraint(node, constraint_param, constraints.visibility_constraints.back()))
509  return false;
510  }
511  else
512  {
513  RCLCPP_ERROR_STREAM(LOGGER, "Unable to process unknown constraint type: " << constraint_type);
514  return false;
515  }
516  }
517 
518  return true;
519 }
520 
521 bool constructConstraints(const rclcpp::Node::SharedPtr& node, const std::string& constraints_param,
522  moveit_msgs::msg::Constraints& constraints)
523 {
524  if (!node->get_parameter(constraints_param + ".name", constraints.name))
525  return false;
526 
527  std::vector<std::string> constraint_ids;
528  if (!node->get_parameter(constraints_param + ".constraint_ids", constraint_ids))
529  return false;
530 
531  for (auto& constraint_id : constraint_ids)
532  constraint_id.insert(0, constraints_param + std::string("."));
533 
534  return collectConstraints(node, constraint_ids, constraints);
535 }
536 } // namespace kinematic_constraints
537 
539  moveit_msgs::msg::Constraints& constraints)
540 {
541  for (auto& c : constraints.position_constraints)
542  {
543  bool frame_found;
544  const moveit::core::LinkModel* robot_link;
545  const Eigen::Isometry3d& transform = state.getFrameInfo(c.link_name, robot_link, frame_found);
546  if (!frame_found)
547  return false;
548 
549  // If the frame of the constraint is not part of the robot link model (but an attached body or subframe),
550  // the constraint needs to be expressed in the frame of a robot link.
551  if (c.link_name != robot_link->getName())
552  {
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;
556 
557  c.link_name = robot_link->getName();
558  tf2::toMsg(offset_robot_link, c.target_point_offset);
559  }
560  }
561 
562  for (auto& c : constraints.orientation_constraints)
563  {
564  bool frame_found;
565  const moveit::core::LinkModel* robot_link;
566  // getFrameInfo() returns a valid isometry by contract
567  const Eigen::Isometry3d& transform = state.getFrameInfo(c.link_name, robot_link, frame_found);
568  if (!frame_found)
569  return false;
570 
571  // If the frame of the constraint is not part of the robot link model (but an attached body or subframe),
572  // the constraint needs to be expressed in the frame of a robot link.
573  if (c.link_name != robot_link->getName())
574  {
575  c.link_name = robot_link->getName();
576  Eigen::Quaterniond link_name_to_robot_link(transform.linear().transpose() *
577  state.getGlobalLinkTransform(robot_link).linear());
578  Eigen::Quaterniond quat_target;
579  tf2::fromMsg(c.orientation, quat_target);
580  c.orientation = tf2::toMsg(quat_target * link_name_to_robot_link);
581  }
582  }
583  return true;
584 }
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.
Definition: link_model.h:72
const std::string & getName() const
The name of this link.
Definition: link_model.h:86
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
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...
Definition: robot_state.h:1339
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...
Definition: robot_state.h:691
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
Definition: fcl_compat.h:89
Representation and evaluation of kinematic constraints.
std::size_t countIndividualConstraints(const moveit_msgs::msg::Constraints &constr)
Definition: utils.cpp:132
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....
Definition: utils.cpp:144
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.
Definition: utils.cpp:521
moveit_msgs::msg::Constraints mergeConstraints(const moveit_msgs::msg::Constraints &first, const moveit_msgs::msg::Constraints &second)
Merge two sets of constraints into one.
Definition: utils.cpp:56
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.
p
Definition: pick.py:62
a
Definition: plan.py:54
r
Definition: plan.py:56