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