moveit2
The MoveIt Motion Planning Framework for ROS 2.
robot_trajectory.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, 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, Adam Leeper */
36 
37 #include <math.h>
40 #include <rclcpp/duration.hpp>
41 #include <rclcpp/logger.hpp>
42 #include <rclcpp/logging.hpp>
43 #include <rclcpp/time.hpp>
44 #include <tf2_eigen/tf2_eigen.hpp>
45 #include <numeric>
46 #include <optional>
47 
48 namespace robot_trajectory
49 {
50 RobotTrajectory::RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model)
51  : robot_model_(robot_model), group_(nullptr)
52 {
53 }
54 
55 RobotTrajectory::RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group)
56  : robot_model_(robot_model), group_(group.empty() ? nullptr : robot_model->getJointModelGroup(group))
57 {
58 }
59 
60 RobotTrajectory::RobotTrajectory(const moveit::core::RobotModelConstPtr& robot_model,
62  : robot_model_(robot_model), group_(group)
63 {
64 }
65 
67 {
68  *this = other; // default assignment operator performs a shallow copy
69  if (deepcopy)
70  {
71  this->waypoints_.clear();
72  for (const auto& waypoint : other.waypoints_)
73  {
74  this->waypoints_.emplace_back(std::make_shared<moveit::core::RobotState>(*waypoint));
75  }
76  }
77 }
78 
79 const std::string& RobotTrajectory::getGroupName() const
80 {
81  if (group_)
82  return group_->getName();
83  static const std::string EMPTY;
84  return EMPTY;
85 }
86 
88 {
89  return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0);
90 }
91 
93 {
94  if (duration_from_previous_.empty())
95  {
96  RCLCPP_WARN(rclcpp::get_logger("RobotTrajectory"), "Too few waypoints to calculate a duration. Returning 0.");
97  return 0.0;
98  }
99 
100  // If the initial segment has a duration of 0, exclude it from the average calculation
101  if (duration_from_previous_[0] == 0)
102  {
103  if (duration_from_previous_.size() <= 1)
104  {
105  RCLCPP_WARN(rclcpp::get_logger("RobotTrajectory"), "First and only waypoint has a duration of 0.");
106  return 0.0;
107  }
108  else
109  return getDuration() / static_cast<double>(duration_from_previous_.size() - 1);
110  }
111  else
112  return getDuration() / static_cast<double>(duration_from_previous_.size());
113 }
114 
116 {
117  robot_model_.swap(other.robot_model_);
118  std::swap(group_, other.group_);
119  waypoints_.swap(other.waypoints_);
120  duration_from_previous_.swap(other.duration_from_previous_);
121 }
122 
123 RobotTrajectory& RobotTrajectory::append(const RobotTrajectory& source, double dt, size_t start_index, size_t end_index)
124 {
125  end_index = std::min(end_index, source.waypoints_.size());
126  if (start_index >= end_index)
127  return *this;
128  waypoints_.insert(waypoints_.end(), std::next(source.waypoints_.begin(), start_index),
129  std::next(source.waypoints_.begin(), end_index));
130  std::size_t index = duration_from_previous_.size();
131  duration_from_previous_.insert(duration_from_previous_.end(),
132  std::next(source.duration_from_previous_.begin(), start_index),
133  std::next(source.duration_from_previous_.begin(), end_index));
134  if (duration_from_previous_.size() > index)
135  duration_from_previous_[index] += dt;
136 
137  return *this;
138 }
139 
141 {
142  std::reverse(waypoints_.begin(), waypoints_.end());
143  for (moveit::core::RobotStatePtr& waypoint : waypoints_)
144  {
145  // reversing the trajectory implies inverting the velocity profile
146  waypoint->invertVelocity();
147  }
148  if (!duration_from_previous_.empty())
149  {
150  duration_from_previous_.push_back(duration_from_previous_.front());
151  std::reverse(duration_from_previous_.begin(), duration_from_previous_.end());
152  duration_from_previous_.pop_back();
153  }
154 
155  return *this;
156 }
157 
159 {
160  if (waypoints_.empty())
161  return *this;
162 
163  const std::vector<const moveit::core::JointModel*>& cont_joints =
164  group_ ? group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
165 
166  for (const moveit::core::JointModel* cont_joint : cont_joints)
167  {
168  // unwrap continuous joints
169  double running_offset = 0.0;
170  double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
171 
172  for (std::size_t j = 1; j < waypoints_.size(); ++j)
173  {
174  double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
175  if (last_value > current_value + M_PI)
176  running_offset += 2.0 * M_PI;
177  else if (current_value > last_value + M_PI)
178  running_offset -= 2.0 * M_PI;
179 
180  last_value = current_value;
181  if (running_offset > std::numeric_limits<double>::epsilon() ||
182  running_offset < -std::numeric_limits<double>::epsilon())
183  {
184  current_value += running_offset;
185  waypoints_[j]->setJointPositions(cont_joint, &current_value);
186  }
187  }
188  }
189  for (moveit::core::RobotStatePtr& waypoint : waypoints_)
190  waypoint->update();
191 
192  return *this;
193 }
194 
196 {
197  if (waypoints_.empty())
198  return *this;
199 
200  const std::vector<const moveit::core::JointModel*>& cont_joints =
201  group_ ? group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
202 
203  for (const moveit::core::JointModel* cont_joint : cont_joints)
204  {
205  double reference_value0 = state.getJointPositions(cont_joint)[0];
206  double reference_value = reference_value0;
207  cont_joint->enforcePositionBounds(&reference_value);
208 
209  // unwrap continuous joints
210  double running_offset = reference_value0 - reference_value;
211 
212  double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
213  if (running_offset > std::numeric_limits<double>::epsilon() ||
214  running_offset < -std::numeric_limits<double>::epsilon())
215  {
216  double current_value = last_value + running_offset;
217  waypoints_[0]->setJointPositions(cont_joint, &current_value);
218  }
219 
220  for (std::size_t j = 1; j < waypoints_.size(); ++j)
221  {
222  double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
223  if (last_value > current_value + M_PI)
224  running_offset += 2.0 * M_PI;
225  else if (current_value > last_value + M_PI)
226  running_offset -= 2.0 * M_PI;
227 
228  last_value = current_value;
229  if (running_offset > std::numeric_limits<double>::epsilon() ||
230  running_offset < -std::numeric_limits<double>::epsilon())
231  {
232  current_value += running_offset;
233  waypoints_[j]->setJointPositions(cont_joint, &current_value);
234  }
235  }
236  }
237  for (moveit::core::RobotStatePtr& waypoint : waypoints_)
238  waypoint->update();
239 
240  return *this;
241 }
242 
243 void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory& trajectory,
244  const std::vector<std::string>& joint_filter) const
245 {
246  trajectory = moveit_msgs::msg::RobotTrajectory();
247  if (waypoints_.empty())
248  return;
249  const std::vector<const moveit::core::JointModel*>& jnts =
250  group_ ? group_->getActiveJointModels() : robot_model_->getActiveJointModels();
251 
252  std::vector<const moveit::core::JointModel*> onedof;
253  std::vector<const moveit::core::JointModel*> mdof;
254  trajectory.joint_trajectory.joint_names.clear();
255  trajectory.multi_dof_joint_trajectory.joint_names.clear();
256 
257  for (const moveit::core::JointModel* active_joint : jnts)
258  {
259  // only consider joints listed in joint_filter
260  if (!joint_filter.empty() &&
261  std::find(joint_filter.begin(), joint_filter.end(), active_joint->getName()) == joint_filter.end())
262  continue;
263 
264  if (active_joint->getVariableCount() == 1)
265  {
266  trajectory.joint_trajectory.joint_names.push_back(active_joint->getName());
267  onedof.push_back(active_joint);
268  }
269  else
270  {
271  trajectory.multi_dof_joint_trajectory.joint_names.push_back(active_joint->getName());
272  mdof.push_back(active_joint);
273  }
274  }
275 
276  if (!onedof.empty())
277  {
278  trajectory.joint_trajectory.header.frame_id = robot_model_->getModelFrame();
279  trajectory.joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
280  trajectory.joint_trajectory.points.resize(waypoints_.size());
281  }
282 
283  if (!mdof.empty())
284  {
285  trajectory.multi_dof_joint_trajectory.header.frame_id = robot_model_->getModelFrame();
286  trajectory.multi_dof_joint_trajectory.header.stamp = rclcpp::Time(0, 0, RCL_ROS_TIME);
287  trajectory.multi_dof_joint_trajectory.points.resize(waypoints_.size());
288  }
289 
290  static const auto ZERO_DURATION = rclcpp::Duration::from_seconds(0);
291  double total_time = 0.0;
292  for (std::size_t i = 0; i < waypoints_.size(); ++i)
293  {
294  if (duration_from_previous_.size() > i)
295  total_time += duration_from_previous_[i];
296 
297  if (!onedof.empty())
298  {
299  trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
300  trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
301 
302  for (std::size_t j = 0; j < onedof.size(); ++j)
303  {
304  trajectory.joint_trajectory.points[i].positions[j] =
305  waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
306  // if we have velocities/accelerations/effort, copy those too
307  if (waypoints_[i]->hasVelocities())
308  trajectory.joint_trajectory.points[i].velocities.push_back(
309  waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
310  if (waypoints_[i]->hasAccelerations())
311  trajectory.joint_trajectory.points[i].accelerations.push_back(
312  waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
313  if (waypoints_[i]->hasEffort())
314  trajectory.joint_trajectory.points[i].effort.push_back(
315  waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
316  }
317  // clear velocities if we have an incomplete specification
318  if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
319  trajectory.joint_trajectory.points[i].velocities.clear();
320  // clear accelerations if we have an incomplete specification
321  if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
322  trajectory.joint_trajectory.points[i].accelerations.clear();
323  // clear effort if we have an incomplete specification
324  if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
325  trajectory.joint_trajectory.points[i].effort.clear();
326 
327  if (duration_from_previous_.size() > i)
328  trajectory.joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
329  else
330  trajectory.joint_trajectory.points[i].time_from_start = ZERO_DURATION;
331  }
332  if (!mdof.empty())
333  {
334  trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
335  for (std::size_t j = 0; j < mdof.size(); ++j)
336  {
337  geometry_msgs::msg::TransformStamped ts = tf2::eigenToTransform(waypoints_[i]->getJointTransform(mdof[j]));
338  trajectory.multi_dof_joint_trajectory.points[i].transforms[j] = ts.transform;
339  // TODO: currently only checking for planar multi DOF joints / need to add check for floating
340  if (waypoints_[i]->hasVelocities() && (mdof[j]->getType() == moveit::core::JointModel::JointType::PLANAR))
341  {
342  const std::vector<std::string> names = mdof[j]->getVariableNames();
343  const double* velocities = waypoints_[i]->getJointVelocities(mdof[j]);
344 
345  geometry_msgs::msg::Twist point_velocity;
346 
347  for (std::size_t k = 0; k < names.size(); ++k)
348  {
349  if (names[k].find("/x") != std::string::npos)
350  {
351  point_velocity.linear.x = velocities[k];
352  }
353  else if (names[k].find("/y") != std::string::npos)
354  {
355  point_velocity.linear.y = velocities[k];
356  }
357  else if (names[k].find("/z") != std::string::npos)
358  {
359  point_velocity.linear.z = velocities[k];
360  }
361  else if (names[k].find("/theta") != std::string::npos)
362  {
363  point_velocity.angular.z = velocities[k];
364  }
365  }
366  trajectory.multi_dof_joint_trajectory.points[i].velocities.push_back(point_velocity);
367  }
368  }
369  if (duration_from_previous_.size() > i)
370  trajectory.multi_dof_joint_trajectory.points[i].time_from_start = rclcpp::Duration::from_seconds(total_time);
371  else
372  trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ZERO_DURATION;
373  }
374  }
375 }
376 
378  const trajectory_msgs::msg::JointTrajectory& trajectory)
379 {
380  // make a copy just in case the next clear() removes the memory for the reference passed in
381  const moveit::core::RobotState copy(reference_state); // NOLINT(performance-unnecessary-copy-initialization)
382  clear();
383  std::size_t state_count = trajectory.points.size();
384  rclcpp::Time last_time_stamp = trajectory.header.stamp;
385  rclcpp::Time this_time_stamp = last_time_stamp;
386 
387  for (std::size_t i = 0; i < state_count; ++i)
388  {
389  this_time_stamp = rclcpp::Time(trajectory.header.stamp) + trajectory.points[i].time_from_start;
390  auto st = std::make_shared<moveit::core::RobotState>(copy);
391  st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
392  if (!trajectory.points[i].velocities.empty())
393  st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
394  if (!trajectory.points[i].accelerations.empty())
395  st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
396  if (!trajectory.points[i].effort.empty())
397  st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
398  addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).seconds());
399  last_time_stamp = this_time_stamp;
400  }
401 
402  return *this;
403 }
404 
406  const moveit_msgs::msg::RobotTrajectory& trajectory)
407 {
408  // make a copy just in case the next clear() removes the memory for the reference passed in
409  const moveit::core::RobotState& copy = reference_state;
410  clear();
411 
412  std::size_t state_count =
413  std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
414  rclcpp::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
415  trajectory.multi_dof_joint_trajectory.header.stamp :
416  trajectory.joint_trajectory.header.stamp;
417  rclcpp::Time this_time_stamp = last_time_stamp;
418 
419  for (std::size_t i = 0; i < state_count; ++i)
420  {
421  auto st = std::make_shared<moveit::core::RobotState>(copy);
422  if (trajectory.joint_trajectory.points.size() > i)
423  {
424  st->setVariablePositions(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].positions);
425  if (!trajectory.joint_trajectory.points[i].velocities.empty())
426  st->setVariableVelocities(trajectory.joint_trajectory.joint_names,
427  trajectory.joint_trajectory.points[i].velocities);
428  if (!trajectory.joint_trajectory.points[i].accelerations.empty())
429  st->setVariableAccelerations(trajectory.joint_trajectory.joint_names,
430  trajectory.joint_trajectory.points[i].accelerations);
431  if (!trajectory.joint_trajectory.points[i].effort.empty())
432  st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
433  this_time_stamp = rclcpp::Time(trajectory.joint_trajectory.header.stamp) +
434  trajectory.joint_trajectory.points[i].time_from_start;
435  }
436  if (trajectory.multi_dof_joint_trajectory.points.size() > i)
437  {
438  for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
439  {
440  Eigen::Isometry3d t = tf2::transformToEigen(trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
441  st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j], t);
442  }
443  this_time_stamp = rclcpp::Time(trajectory.multi_dof_joint_trajectory.header.stamp) +
444  trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
445  }
446 
447  addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).seconds());
448  last_time_stamp = this_time_stamp;
449  }
450  return *this;
451 }
452 
454  const moveit_msgs::msg::RobotState& state,
455  const moveit_msgs::msg::RobotTrajectory& trajectory)
456 {
457  moveit::core::RobotState st(reference_state);
459  return setRobotTrajectoryMsg(st, trajectory);
460 }
461 
462 void RobotTrajectory::findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after,
463  double& blend) const
464 {
465  if (duration < 0.0)
466  {
467  before = 0;
468  after = 0;
469  blend = 0;
470  return;
471  }
472 
473  // Find indices
474  std::size_t index = 0, num_points = waypoints_.size();
475  double running_duration = 0.0;
476  for (; index < num_points; ++index)
477  {
478  running_duration += duration_from_previous_[index];
479  if (running_duration >= duration)
480  break;
481  }
482  before = std::max<int>(index - 1, 0);
483  after = std::min<int>(index, num_points - 1);
484 
485  // Compute duration blend
486  double before_time = running_duration - duration_from_previous_[index];
487  if (after == before)
488  blend = 1.0;
489  else
490  blend = (duration - before_time) / duration_from_previous_[index];
491 }
492 
493 double RobotTrajectory::getWayPointDurationFromStart(std::size_t index) const
494 {
495  if (duration_from_previous_.empty())
496  return 0.0;
497  if (index >= duration_from_previous_.size())
498  index = duration_from_previous_.size() - 1;
499 
500  double time = 0.0;
501  for (std::size_t i = 0; i <= index; ++i)
502  time += duration_from_previous_[i];
503  return time;
504 }
505 
506 double RobotTrajectory::getWaypointDurationFromStart(std::size_t index) const
507 {
508  return getWayPointDurationFromStart(index);
509 }
510 
511 bool RobotTrajectory::getStateAtDurationFromStart(const double request_duration,
512  moveit::core::RobotStatePtr& output_state) const
513 {
514  // If there are no waypoints we can't do anything
515  if (getWayPointCount() == 0)
516  return false;
517 
518  int before = 0, after = 0;
519  double blend = 1.0;
520  findWayPointIndicesForDurationAfterStart(request_duration, before, after, blend);
521  // ROS_DEBUG_NAMED("robot_trajectory", "Interpolating %.3f of the way between index %d and %d.", blend, before,
522  // after);
523  waypoints_[before]->interpolate(*waypoints_[after], blend, *output_state);
524  return true;
525 }
526 
527 void RobotTrajectory::print(std::ostream& out, std::vector<int> variable_indexes) const
528 {
529  size_t num_points = getWayPointCount();
530  if (num_points == 0)
531  {
532  out << "Empty trajectory.";
533  return;
534  }
535 
536  std::ios::fmtflags old_settings = out.flags();
537  int old_precision = out.precision();
538  out << std::fixed << std::setprecision(3);
539 
540  out << "Trajectory has " << num_points << " points over " << getDuration() << " seconds\n";
541 
542  if (variable_indexes.empty())
543  {
544  if (group_)
545  {
546  variable_indexes = group_->getVariableIndexList();
547  }
548  else
549  {
550  // use all variables
551  variable_indexes.resize(robot_model_->getVariableCount());
552  std::iota(variable_indexes.begin(), variable_indexes.end(), 0);
553  }
554  }
555 
556  for (size_t p_i = 0; p_i < num_points; ++p_i)
557  {
558  const moveit::core::RobotState& point = getWayPoint(p_i);
559  out << " waypoint " << std::setw(3) << p_i;
560  out << " time " << std::setw(5) << getWayPointDurationFromStart(p_i);
561  out << " pos ";
562  for (int index : variable_indexes)
563  {
564  out << std::setw(6) << point.getVariablePosition(index) << " ";
565  }
566  if (point.hasVelocities())
567  {
568  out << "vel ";
569  for (int index : variable_indexes)
570  {
571  out << std::setw(6) << point.getVariableVelocity(index) << " ";
572  }
573  }
574  if (point.hasAccelerations())
575  {
576  out << "acc ";
577  for (int index : variable_indexes)
578  {
579  out << std::setw(6) << point.getVariableAcceleration(index) << " ";
580  }
581  }
582  if (point.hasEffort())
583  {
584  out << "eff ";
585  for (int index : variable_indexes)
586  {
587  out << std::setw(6) << point.getVariableEffort(index) << " ";
588  }
589  }
590  out << "\n";
591  }
592 
593  out.flags(old_settings);
594  out.precision(old_precision);
595  out.flush();
596 }
597 
598 std::ostream& operator<<(std::ostream& out, const RobotTrajectory& trajectory)
599 {
600  trajectory.print(out);
601  return out;
602 }
603 
604 double path_length(RobotTrajectory const& trajectory)
605 {
606  auto trajectory_length = 0.0;
607  for (std::size_t index = 1; index < trajectory.getWayPointCount(); ++index)
608  {
609  auto const& first = trajectory.getWayPoint(index - 1);
610  auto const& second = trajectory.getWayPoint(index);
611  trajectory_length += first.distance(second);
612  }
613  return trajectory_length;
614 }
615 
616 std::optional<double> smoothness(RobotTrajectory const& trajectory)
617 {
618  if (trajectory.getWayPointCount() > 2)
619  {
620  auto smoothness = 0.0;
621  double a = trajectory.getWayPoint(0).distance(trajectory.getWayPoint(1));
622  for (std::size_t k = 2; k < trajectory.getWayPointCount(); ++k)
623  {
624  // view the path as a sequence of segments, and look at the triangles it forms:
625  // s1
626  // /\ s4
627  // a / \ b |
628  // / \ |
629  // /......\_______|
630  // s0 c s2 s3
631 
632  // use Pythagoras generalized theorem to find the cos of the angle between segments a and b
633  double b = trajectory.getWayPoint(k - 1).distance(trajectory.getWayPoint(k));
634  double cdist = trajectory.getWayPoint(k - 2).distance(trajectory.getWayPoint(k));
635  double acos_value = (a * a + b * b - cdist * cdist) / (2.0 * a * b);
636  if (acos_value > -1.0 && acos_value < 1.0)
637  {
638  // the smoothness is actually the outside angle of the one we compute
639  double angle = (M_PI - acos(acos_value));
640 
641  // and we normalize by the length of the segments
642  double u = 2.0 * angle;
643  smoothness += u * u;
644  }
645  a = b;
646  }
647  smoothness /= (double)trajectory.getWayPointCount();
648  return smoothness;
649  }
650  // In case the path is to short, no value is returned
651  return std::nullopt;
652 }
653 
654 std::optional<double> waypoint_density(RobotTrajectory const& trajectory)
655 {
656  // Only calculate density if more than one waypoint exists
657  if (trajectory.getWayPointCount() > 1)
658  {
659  // Calculate path length
660  auto const length = path_length(trajectory);
661  if (length > 0.0)
662  {
663  auto density = (double)trajectory.getWayPointCount() / length;
664  return density;
665  }
666  }
667  // Trajectory is empty, a single point or path length is zero
668  return std::nullopt;
669 }
670 
671 } // end of namespace robot_trajectory
const std::vector< const JointModel * > & getActiveJointModels() const
Get the active joints in this group (that have controllable DOF). This does not include mimic joints.
const std::string & getName() const
Get the name of the joint group.
const std::vector< const JointModel * > & getContinuousJointModels() const
Get the array of continuous joints used in this group (may include mimic joints).
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group.
A joint from the robot. Models the transform that this joint applies in the kinematic chain....
Definition: joint_model.h:117
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
double getVariableAcceleration(const std::string &variable) const
Get the acceleration of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:395
const double * getJointPositions(const std::string &joint_name) const
Definition: robot_state.h:557
bool hasVelocities() const
By default, if velocities are never set or initialized, the state remembers that there are no velocit...
Definition: robot_state.h:229
double getVariableVelocity(const std::string &variable) const
Get the velocity of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:296
bool hasAccelerations() const
By default, if accelerations are never set or initialized, the state remembers that there are no acce...
Definition: robot_state.h:322
bool hasEffort() const
By default, if effort is never set or initialized, the state remembers that there is no effort set....
Definition: robot_state.h:420
double * getVariableEffort()
Get raw access to the effort of the variables that make up this state. The values are in the same ord...
Definition: robot_state.h:428
double distance(const RobotState &other) const
Return the sum of joint distances to "other" state. An L1 norm. Only considers active joints.
Definition: robot_state.h:1457
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
Definition: robot_state.h:207
Maintain a sequence of waypoints and the time durations between these waypoints.
void swap(robot_trajectory::RobotTrajectory &other)
double getWaypointDurationFromStart(std::size_t index) const
const std::string & getGroupName() const
double getWayPointDurationFromStart(std::size_t index) const
Returns the duration after start that a waypoint will be reached.
RobotTrajectory(const moveit::core::RobotModelConstPtr &robot_model)
construct a trajectory for the whole robot
void print(std::ostream &out, std::vector< int > variable_indexes=std::vector< int >()) const
Print information about the trajectory.
bool getStateAtDurationFromStart(const double request_duration, moveit::core::RobotStatePtr &output_state) const
Gets a robot state corresponding to a supplied duration from start for the trajectory,...
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
RobotTrajectory & setRobotTrajectoryMsg(const moveit::core::RobotState &reference_state, const trajectory_msgs::msg::JointTrajectory &trajectory)
Copy the content of the trajectory message into this class. The trajectory message itself is not requ...
RobotTrajectory & append(const RobotTrajectory &source, double dt, size_t start_index=0, size_t end_index=std::numeric_limits< std::size_t >::max())
Add a specified part of a trajectory to the end of the current trajectory. The default (when start_in...
void findWayPointIndicesForDurationAfterStart(const double &duration, int &before, int &after, double &blend) const
Finds the waypoint indices before and after a duration from start.
const moveit::core::RobotState & getWayPoint(std::size_t index) const
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
a
Definition: plan.py:54
double path_length(RobotTrajectory const &trajectory)
Calculate the path length of a given trajectory based on the accumulated robot state distances....
std::optional< double > waypoint_density(RobotTrajectory const &trajectory)
Calculate the waypoint density of a trajectory.
std::ostream & operator<<(std::ostream &out, const RobotTrajectory &trajectory)
Operator overload for printing trajectory to a stream.
std::optional< double > smoothness(RobotTrajectory const &trajectory)
Calculate the smoothness of a given trajectory.