moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_functions.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 
36 
38 #include <tf2/LinearMath/Quaternion.h>
39 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
40 #include <tf2_eigen/tf2_eigen.hpp>
41 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
42 
43 namespace
44 {
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner.trajectory_functions");
46 }
47 
48 bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr& scene,
49  const std::string& group_name, const std::string& link_name,
50  const Eigen::Isometry3d& pose, const std::string& frame_id,
51  const std::map<std::string, double>& seed,
52  std::map<std::string, double>& solution, bool check_self_collision,
53  const double timeout)
54 {
55  const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
56  if (!robot_model->hasJointModelGroup(group_name))
57  {
58  RCLCPP_ERROR_STREAM(LOGGER, "Robot model has no planning group named as " << group_name);
59  return false;
60  }
61 
62  if (frame_id != robot_model->getModelFrame())
63  {
64  RCLCPP_ERROR_STREAM(LOGGER, "Given frame (" << frame_id << ") is unequal to model frame("
65  << robot_model->getModelFrame() << ")");
66  return false;
67  }
68 
69  moveit::core::RobotState rstate{ scene->getCurrentState() };
70  rstate.setVariablePositions(seed);
71 
72  moveit::core::GroupStateValidityCallbackFn ik_constraint_function;
73  if (check_self_collision)
74  {
75  ik_constraint_function = [scene](moveit::core::RobotState* robot_state,
76  const moveit::core::JointModelGroup* joint_group,
77  const double* joint_group_variable_values) {
78  return pilz_industrial_motion_planner::isStateColliding(scene, robot_state, joint_group,
79  joint_group_variable_values);
80  };
81  }
82 
83  // call ik
84  const moveit::core::JointModelGroup* jmg = robot_model->getJointModelGroup(group_name);
85  if (rstate.setFromIK(jmg, pose, link_name, timeout, ik_constraint_function))
86  {
87  // copy the solution
88  for (const auto& joint_name : jmg->getActiveJointModelNames())
89  {
90  solution[joint_name] = rstate.getVariablePosition(joint_name);
91  }
92  return true;
93  }
94  else
95  {
96  RCLCPP_ERROR(LOGGER, "Unable to find IK solution.");
97  // TODO(henning): Re-enable logging error
98  // RCLCPP_ERROR_STREAM(LOGGER, "Inverse kinematics for pose \n" << pose.translation() << " has no solution.");
99  return false;
100  }
101 }
102 
103 bool pilz_industrial_motion_planner::computePoseIK(const planning_scene::PlanningSceneConstPtr& scene,
104  const std::string& group_name, const std::string& link_name,
105  const geometry_msgs::msg::Pose& pose, const std::string& frame_id,
106  const std::map<std::string, double>& seed,
107  std::map<std::string, double>& solution, bool check_self_collision,
108  const double timeout)
109 {
110  Eigen::Isometry3d pose_eigen;
111  tf2::convert<geometry_msgs::msg::Pose, Eigen::Isometry3d>(pose, pose_eigen);
112  return computePoseIK(scene, group_name, link_name, pose_eigen, frame_id, seed, solution, check_self_collision,
113  timeout);
114 }
115 
116 bool pilz_industrial_motion_planner::computeLinkFK(moveit::core::RobotState& robot_state, const std::string& link_name,
117  const std::map<std::string, double>& joint_state,
118  Eigen::Isometry3d& pose)
119 {
120  // check the reference frame of the target pose
121  if (!robot_state.knowsFrameTransform(link_name))
122  {
123  RCLCPP_ERROR_STREAM(LOGGER, "The target link " << link_name << " is not known by robot.");
124  return false;
125  }
126 
127  robot_state.setVariablePositions(joint_state);
128 
129  // update the frame
130  robot_state.update();
131  pose = robot_state.getFrameTransform(link_name);
132 
133  return true;
134 }
135 
137  const std::map<std::string, double>& position_last, const std::map<std::string, double>& velocity_last,
138  const std::map<std::string, double>& position_current, double duration_last, double duration_current,
140 {
141  const double epsilon = 10e-6;
142  if (duration_current <= epsilon)
143  {
144  RCLCPP_ERROR(LOGGER, "Sample duration too small, cannot compute the velocity");
145  return false;
146  }
147 
148  double velocity_current, acceleration_current;
149 
150  for (const auto& pos : position_current)
151  {
152  velocity_current = (pos.second - position_last.at(pos.first)) / duration_current;
153 
154  if (!joint_limits.verifyVelocityLimit(pos.first, velocity_current))
155  {
156  RCLCPP_ERROR_STREAM(LOGGER, "Joint velocity limit of "
157  << pos.first << " violated. Set the velocity scaling factor lower!"
158  << " Actual joint velocity is " << velocity_current << ", while the limit is "
159  << joint_limits.getLimit(pos.first).max_velocity << ". ");
160  return false;
161  }
162 
163  acceleration_current = (velocity_current - velocity_last.at(pos.first)) / (duration_last + duration_current) * 2;
164  // acceleration case
165  if (fabs(velocity_last.at(pos.first)) <= fabs(velocity_current))
166  {
167  if (joint_limits.getLimit(pos.first).has_acceleration_limits &&
168  fabs(acceleration_current) > fabs(joint_limits.getLimit(pos.first).max_acceleration))
169  {
170  RCLCPP_ERROR_STREAM(LOGGER, "Joint acceleration limit of "
171  << pos.first << " violated. Set the acceleration scaling factor lower!"
172  << " Actual joint acceleration is " << acceleration_current
173  << ", while the limit is " << joint_limits.getLimit(pos.first).max_acceleration
174  << ". ");
175  return false;
176  }
177  }
178  // deceleration case
179  else
180  {
181  if (joint_limits.getLimit(pos.first).has_deceleration_limits &&
182  fabs(acceleration_current) > fabs(joint_limits.getLimit(pos.first).max_deceleration))
183  {
184  RCLCPP_ERROR_STREAM(LOGGER, "Joint deceleration limit of "
185  << pos.first << " violated. Set the acceleration scaling factor lower!"
186  << " Actual joint deceleration is " << acceleration_current
187  << ", while the limit is " << joint_limits.getLimit(pos.first).max_deceleration
188  << ". ");
189  return false;
190  }
191  }
192  }
193 
194  return true;
195 }
196 
198  const planning_scene::PlanningSceneConstPtr& scene,
199  const pilz_industrial_motion_planner::JointLimitsContainer& joint_limits, const KDL::Trajectory& trajectory,
200  const std::string& group_name, const std::string& link_name,
201  const std::map<std::string, double>& initial_joint_position, const double& sampling_time,
202  trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
203  bool check_self_collision)
204 {
205  RCLCPP_DEBUG(LOGGER, "Generate joint trajectory from a Cartesian trajectory.");
206 
207  const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
208  rclcpp::Clock clock;
209  rclcpp::Time generation_begin = clock.now();
210 
211  // generate the time samples
212  const double epsilon = 10e-06; // avoid adding the last time sample twice
213  std::vector<double> time_samples;
214  for (double t_sample = 0.0; t_sample < trajectory.Duration() - epsilon; t_sample += sampling_time)
215  {
216  time_samples.push_back(t_sample);
217  }
218  time_samples.push_back(trajectory.Duration());
219 
220  // sample the trajectory and solve the inverse kinematics
221  Eigen::Isometry3d pose_sample;
222  std::map<std::string, double> ik_solution_last, ik_solution, joint_velocity_last;
223  ik_solution_last = initial_joint_position;
224  for (const auto& item : ik_solution_last)
225  {
226  joint_velocity_last[item.first] = 0.0;
227  }
228 
229  for (std::vector<double>::const_iterator time_iter = time_samples.begin(); time_iter != time_samples.end();
230  ++time_iter)
231  {
232  tf2::transformKDLToEigen(trajectory.Pos(*time_iter), pose_sample);
233 
234  if (!computePoseIK(scene, group_name, link_name, pose_sample, robot_model->getModelFrame(), ik_solution_last,
235  ik_solution, check_self_collision))
236  {
237  RCLCPP_ERROR(LOGGER, "Failed to compute inverse kinematics solution for sampled Cartesian pose.");
238  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
239  joint_trajectory.points.clear();
240  return false;
241  }
242 
243  // check the joint limits
244  double duration_current_sample = sampling_time;
245  // last interval can be shorter than the sampling time
246  if (time_iter == (time_samples.end() - 1) && time_samples.size() > 1)
247  {
248  duration_current_sample = *time_iter - *(time_iter - 1);
249  }
250  if (time_samples.size() == 1)
251  {
252  duration_current_sample = *time_iter;
253  }
254 
255  // skip the first sample with zero time from start for limits checking
256  if (time_iter != time_samples.begin() &&
257  !verifySampleJointLimits(ik_solution_last, joint_velocity_last, ik_solution, sampling_time,
258  duration_current_sample, joint_limits))
259  {
260  RCLCPP_ERROR_STREAM(LOGGER, "Inverse kinematics solution at "
261  << *time_iter
262  << "s violates the joint velocity/acceleration/deceleration limits.");
263  error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
264  joint_trajectory.points.clear();
265  return false;
266  }
267 
268  // fill the point with joint values
269  trajectory_msgs::msg::JointTrajectoryPoint point;
270 
271  // set joint names
272  joint_trajectory.joint_names.clear();
273  for (const auto& start_joint : initial_joint_position)
274  {
275  joint_trajectory.joint_names.push_back(start_joint.first);
276  }
277 
278  point.time_from_start = rclcpp::Duration::from_seconds(*time_iter);
279  for (const auto& joint_name : joint_trajectory.joint_names)
280  {
281  point.positions.push_back(ik_solution.at(joint_name));
282 
283  if (time_iter != time_samples.begin() && time_iter != time_samples.end() - 1)
284  {
285  double joint_velocity =
286  (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current_sample;
287  point.velocities.push_back(joint_velocity);
288  point.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
289  (duration_current_sample + sampling_time) * 2);
290  joint_velocity_last[joint_name] = joint_velocity;
291  }
292  else
293  {
294  point.velocities.push_back(0.);
295  point.accelerations.push_back(0.);
296  joint_velocity_last[joint_name] = 0.;
297  }
298  }
299 
300  // update joint trajectory
301  joint_trajectory.points.push_back(point);
302  ik_solution_last = ik_solution;
303  }
304 
305  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
306  double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
307  RCLCPP_DEBUG_STREAM(LOGGER, "Generate trajectory (N-Points: "
308  << joint_trajectory.points.size() << ") took " << duration_ms << " ms | "
309  << duration_ms / joint_trajectory.points.size() << " ms per Point");
310 
311  return true;
312 }
313 
315  const planning_scene::PlanningSceneConstPtr& scene,
317  const pilz_industrial_motion_planner::CartesianTrajectory& trajectory, const std::string& group_name,
318  const std::string& link_name, const std::map<std::string, double>& initial_joint_position,
319  const std::map<std::string, double>& initial_joint_velocity,
320  trajectory_msgs::msg::JointTrajectory& joint_trajectory, moveit_msgs::msg::MoveItErrorCodes& error_code,
321  bool check_self_collision)
322 {
323  RCLCPP_DEBUG(LOGGER, "Generate joint trajectory from a Cartesian trajectory.");
324 
325  const moveit::core::RobotModelConstPtr& robot_model = scene->getRobotModel();
326  rclcpp::Clock clock;
327  rclcpp::Time generation_begin = clock.now();
328 
329  std::map<std::string, double> ik_solution_last = initial_joint_position;
330  std::map<std::string, double> joint_velocity_last = initial_joint_velocity;
331  double duration_last = 0;
332  double duration_current = 0;
333  joint_trajectory.joint_names.clear();
334  for (const auto& joint_position : ik_solution_last)
335  {
336  joint_trajectory.joint_names.push_back(joint_position.first);
337  }
338  std::map<std::string, double> ik_solution;
339  for (size_t i = 0; i < trajectory.points.size(); ++i)
340  {
341  // compute inverse kinematics
342  if (!computePoseIK(scene, group_name, link_name, trajectory.points.at(i).pose, robot_model->getModelFrame(),
343  ik_solution_last, ik_solution, check_self_collision))
344  {
345  RCLCPP_ERROR(LOGGER, "Failed to compute inverse kinematics solution for sampled "
346  "Cartesian pose.");
347  error_code.val = moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION;
348  joint_trajectory.points.clear();
349  return false;
350  }
351 
352  // verify the joint limits
353  if (i == 0)
354  {
355  duration_current = trajectory.points.front().time_from_start.seconds();
356  duration_last = duration_current;
357  }
358  else
359  {
360  duration_current =
361  trajectory.points.at(i).time_from_start.seconds() - trajectory.points.at(i - 1).time_from_start.seconds();
362  }
363 
364  if (!verifySampleJointLimits(ik_solution_last, joint_velocity_last, ik_solution, duration_last, duration_current,
365  joint_limits))
366  {
367  // LCOV_EXCL_START since the same code was captured in a test in the other
368  // overload generateJointTrajectory(...,
369  // KDL::Trajectory, ...)
370  // TODO: refactor to avoid code duplication.
371  RCLCPP_ERROR_STREAM(LOGGER, "Inverse kinematics solution of the "
372  << i
373  << "th sample violates the joint "
374  "velocity/acceleration/deceleration limits.");
375  error_code.val = moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED;
376  joint_trajectory.points.clear();
377  return false;
378  // LCOV_EXCL_STOP
379  }
380 
381  // compute the waypoint
382  trajectory_msgs::msg::JointTrajectoryPoint waypoint_joint;
383  waypoint_joint.time_from_start = trajectory.points.at(i).time_from_start;
384  for (const auto& joint_name : joint_trajectory.joint_names)
385  {
386  waypoint_joint.positions.push_back(ik_solution.at(joint_name));
387  double joint_velocity = (ik_solution.at(joint_name) - ik_solution_last.at(joint_name)) / duration_current;
388  waypoint_joint.velocities.push_back(joint_velocity);
389  waypoint_joint.accelerations.push_back((joint_velocity - joint_velocity_last.at(joint_name)) /
390  (duration_current + duration_last) * 2);
391  // update the joint velocity
392  joint_velocity_last[joint_name] = joint_velocity;
393  }
394 
395  // update joint trajectory
396  joint_trajectory.points.push_back(waypoint_joint);
397  ik_solution_last = ik_solution;
398  duration_last = duration_current;
399  }
400 
401  error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
402 
403  double duration_ms = (clock.now() - generation_begin).seconds() * 1000;
404  RCLCPP_DEBUG_STREAM(LOGGER, "Generate trajectory (N-Points: "
405  << joint_trajectory.points.size() << ") took " << duration_ms << " ms | "
406  << duration_ms / joint_trajectory.points.size() << " ms per Point");
407 
408  return true;
409 }
410 
412  const robot_trajectory::RobotTrajectoryPtr& first_trajectory,
413  const robot_trajectory::RobotTrajectoryPtr& second_trajectory, double epsilon, double& sampling_time)
414 {
415  // The last sample is ignored because it is allowed to violate the sampling
416  // time.
417  std::size_t n1 = first_trajectory->getWayPointCount() - 1;
418  std::size_t n2 = second_trajectory->getWayPointCount() - 1;
419  if ((n1 < 2) && (n2 < 2))
420  {
421  RCLCPP_ERROR_STREAM(LOGGER, "Both trajectories do not have enough points to determine sampling time.");
422  return false;
423  }
424 
425  if (n1 >= 2)
426  {
427  sampling_time = first_trajectory->getWayPointDurationFromPrevious(1);
428  }
429  else
430  {
431  sampling_time = second_trajectory->getWayPointDurationFromPrevious(1);
432  }
433 
434  for (std::size_t i = 1; i < std::max(n1, n2); ++i)
435  {
436  if (i < n1)
437  {
438  if (fabs(sampling_time - first_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
439  {
440  RCLCPP_ERROR_STREAM(LOGGER, "First trajectory violates sampline time " << sampling_time << " between points "
441  << (i - 1) << "and " << i
442  << " (indices).");
443  return false;
444  }
445  }
446 
447  if (i < n2)
448  {
449  if (fabs(sampling_time - second_trajectory->getWayPointDurationFromPrevious(i)) > epsilon)
450  {
451  RCLCPP_ERROR_STREAM(LOGGER, "Second trajectory violates sampline time " << sampling_time << " between points "
452  << (i - 1) << "and " << i
453  << " (indices).");
454  return false;
455  }
456  }
457  }
458 
459  return true;
460 }
461 
463  const moveit::core::RobotState& state2,
464  const std::string& joint_group_name, double epsilon)
465 {
466  Eigen::VectorXd joint_position_1, joint_position_2;
467 
468  state1.copyJointGroupPositions(joint_group_name, joint_position_1);
469  state2.copyJointGroupPositions(joint_group_name, joint_position_2);
470 
471  if ((joint_position_1 - joint_position_2).norm() > epsilon)
472  {
473  RCLCPP_DEBUG_STREAM(LOGGER, "Joint positions of the two states are different. state1: "
474  << joint_position_1 << " state2: " << joint_position_2);
475  return false;
476  }
477 
478  Eigen::VectorXd joint_velocity_1, joint_velocity_2;
479 
480  state1.copyJointGroupVelocities(joint_group_name, joint_velocity_1);
481  state2.copyJointGroupVelocities(joint_group_name, joint_velocity_2);
482 
483  if ((joint_velocity_1 - joint_velocity_2).norm() > epsilon)
484  {
485  RCLCPP_DEBUG_STREAM(LOGGER, "Joint velocities of the two states are different. state1: "
486  << joint_velocity_1 << " state2: " << joint_velocity_2);
487  return false;
488  }
489 
490  Eigen::VectorXd joint_acc_1, joint_acc_2;
491 
492  state1.copyJointGroupAccelerations(joint_group_name, joint_acc_1);
493  state2.copyJointGroupAccelerations(joint_group_name, joint_acc_2);
494 
495  if ((joint_acc_1 - joint_acc_2).norm() > epsilon)
496  {
497  RCLCPP_DEBUG_STREAM(LOGGER, "Joint accelerations of the two states are different. state1: "
498  << joint_acc_1 << " state2: " << joint_acc_2);
499  return false;
500  }
501 
502  return true;
503 }
504 
506  const std::string& group, double EPSILON)
507 {
508  Eigen::VectorXd joint_variable;
509  state.copyJointGroupVelocities(group, joint_variable);
510  if (joint_variable.norm() > EPSILON)
511  {
512  RCLCPP_DEBUG(LOGGER, "Joint velocities are not zero.");
513  return false;
514  }
515  state.copyJointGroupAccelerations(group, joint_variable);
516  if (joint_variable.norm() > EPSILON)
517  {
518  RCLCPP_DEBUG(LOGGER, "Joint accelerations are not zero.");
519  return false;
520  }
521  return true;
522 }
523 
525  const Eigen::Vector3d& center_position,
526  const double& r,
527  const robot_trajectory::RobotTrajectoryPtr& traj,
528  bool inverseOrder, std::size_t& index)
529 {
530  RCLCPP_DEBUG(LOGGER, "Start linear search for intersection point.");
531 
532  const size_t waypoint_num = traj->getWayPointCount();
533 
534  if (inverseOrder)
535  {
536  for (size_t i = waypoint_num - 1; i > 0; --i)
537  {
538  if (intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
539  traj->getWayPointPtr(i - 1)->getFrameTransform(link_name).translation(), r))
540  {
541  index = i;
542  return true;
543  }
544  }
545  }
546  else
547  {
548  for (size_t i = 0; i < waypoint_num - 1; ++i)
549  {
550  if (intersectionFound(center_position, traj->getWayPointPtr(i)->getFrameTransform(link_name).translation(),
551  traj->getWayPointPtr(i + 1)->getFrameTransform(link_name).translation(), r))
552  {
553  index = i;
554  return true;
555  }
556  }
557  }
558 
559  return false;
560 }
561 
563  const Eigen::Vector3d& p_current, const Eigen::Vector3d& p_next,
564  const double& r)
565 {
566  return ((p_current - p_center).norm() <= r) && ((p_next - p_center).norm() >= r);
567 }
568 
569 bool pilz_industrial_motion_planner::isStateColliding(const planning_scene::PlanningSceneConstPtr& scene,
570  moveit::core::RobotState* rstate,
572  const double* const ik_solution)
573 {
574  rstate->setJointGroupPositions(group, ik_solution);
575  rstate->update();
577  collision_req.group_name = group->getName();
578  collision_req.verbose = true;
580  scene->checkSelfCollision(collision_req, collision_res, *rstate);
581  return !collision_res.collision;
582 }
583 
584 void normalizeQuaternion(geometry_msgs::msg::Quaternion& quat)
585 {
586  tf2::Quaternion q;
587  tf2::convert<geometry_msgs::msg::Quaternion, tf2::Quaternion>(quat, q);
588  quat = tf2::toMsg(q.normalized());
589 }
590 
591 Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point& position,
592  const geometry_msgs::msg::Quaternion& orientation,
593  const geometry_msgs::msg::Vector3& offset)
594 {
595  Eigen::Quaterniond quat;
596  tf2::fromMsg(orientation, quat);
597  quat.normalize();
598  Eigen::Vector3d v;
599  tf2::fromMsg(position, v);
600 
601  Eigen::Isometry3d pose = Eigen::Translation3d(v) * quat;
602 
603  tf2::fromMsg(offset, v);
604  pose.translation() -= quat * v;
605  return pose;
606 }
607 
608 Eigen::Isometry3d getConstraintPose(const moveit_msgs::msg::Constraints& goal)
609 {
610  return getConstraintPose(goal.position_constraints.front().constraint_region.primitive_poses.front().position,
611  goal.orientation_constraints.front().orientation,
612  goal.position_constraints.front().target_point_offset);
613 }
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void copyJointGroupVelocities(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the velocity values of the variables that make up the group into another loca...
Definition: robot_state.h:791
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:605
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 & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
void copyJointGroupAccelerations(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the acceleration values of the variables that make up the group into another ...
Definition: robot_state.h:891
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
std::function< bool(RobotState *robot_state, const JointModelGroup *joint_group, const double *joint_group_variable_values)> GroupStateValidityCallbackFn
Signature for functions that can verify that if the group joint_group in robot_state is set to joint_...
Definition: robot_state.h:70
frame_id
Definition: pick.py:63
scene
Definition: pick.py:52
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, const double &sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool linearSearchIntersectionPoint(const std::string &link_name, const Eigen::Vector3d &center_position, const double &r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
Performs a linear search for the intersection point of the trajectory with the blending radius.
bool isStateColliding(const planning_scene::PlanningSceneConstPtr &scene, moveit::core::RobotState *state, const moveit::core::JointModelGroup *const group, const double *const ik_solution)
Checks if current robot state is in self collision.
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool verifySampleJointLimits(const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
verify the velocity/acceleration limits of current sample (based on backward difference computation) ...
bool intersectionFound(const Eigen::Vector3d &p_center, const Eigen::Vector3d &p_current, const Eigen::Vector3d &p_next, const double &r)
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
r
Definition: plan.py:56
const rclcpp::Logger LOGGER
Definition: async_test.h:31
Representation of a collision checking request.
std::string group_name
The group name to check collisions for (optional; if empty, assume the complete robot)
bool verbose
Flag indicating whether information about detected collisions should be reported.
Representation of a collision checking result.
bool collision
True if collision was found, false otherwise.
std::vector< CartesianTrajectoryPoint > points
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)
Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point &position, const geometry_msgs::msg::Quaternion &orientation, const geometry_msgs::msg::Vector3 &offset)
Adapt goal pose, defined by position+orientation, to consider offset.