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