40 #include <boost/math/constants/constants.hpp>
50 RobotTrajectory::RobotTrajectory(
const moveit::core::RobotModelConstPtr&
robot_model,
const std::string& group)
55 RobotTrajectory::RobotTrajectory(
const moveit::core::RobotModelConstPtr&
robot_model,
61 RobotTrajectory::RobotTrajectory(
const RobotTrajectory& other,
bool deepcopy)
66 this->waypoints_.clear();
67 for (
const auto& waypoint : other.waypoints_)
69 this->waypoints_.emplace_back(std::make_shared<moveit::core::RobotState>(*waypoint));
74 const std::string& RobotTrajectory::getGroupName()
const
77 return group_->getName();
78 static const std::string EMPTY;
82 double RobotTrajectory::getDuration()
const
84 return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0);
87 double RobotTrajectory::getAverageSegmentDuration()
const
89 if (duration_from_previous_.empty())
92 return getDuration() /
static_cast<double>(duration_from_previous_.size());
98 std::swap(group_, other.
group_);
103 RobotTrajectory& RobotTrajectory::append(
const RobotTrajectory& source,
double dt,
size_t start_index,
size_t end_index)
105 end_index = std::min(end_index, source.waypoints_.size());
106 if (start_index >= end_index)
108 waypoints_.insert(waypoints_.end(), std::next(source.waypoints_.begin(), start_index),
109 std::next(source.waypoints_.begin(), end_index));
110 std::size_t
index = duration_from_previous_.size();
111 duration_from_previous_.insert(duration_from_previous_.end(),
112 std::next(source.duration_from_previous_.begin(), start_index),
113 std::next(source.duration_from_previous_.begin(), end_index));
114 if (duration_from_previous_.size() > index)
115 duration_from_previous_[
index] = dt;
122 std::reverse(waypoints_.begin(), waypoints_.end());
123 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
126 waypoint->invertVelocity();
128 if (!duration_from_previous_.empty())
130 duration_from_previous_.push_back(duration_from_previous_.front());
131 std::reverse(duration_from_previous_.begin(), duration_from_previous_.end());
132 duration_from_previous_.pop_back();
140 if (waypoints_.empty())
143 const std::vector<const moveit::core::JointModel*>& cont_joints =
144 group_ ? group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
149 double running_offset = 0.0;
150 double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
152 for (std::size_t j = 1; j < waypoints_.size(); ++j)
154 double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
155 if (last_value > current_value + boost::math::constants::pi<double>())
156 running_offset += 2.0 * boost::math::constants::pi<double>();
157 else if (current_value > last_value + boost::math::constants::pi<double>())
158 running_offset -= 2.0 * boost::math::constants::pi<double>();
160 last_value = current_value;
161 if (running_offset > std::numeric_limits<double>::epsilon() ||
162 running_offset < -std::numeric_limits<double>::epsilon())
164 current_value += running_offset;
165 waypoints_[j]->setJointPositions(cont_joint, ¤t_value);
169 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
177 if (waypoints_.empty())
180 const std::vector<const moveit::core::JointModel*>& cont_joints =
181 group_ ? group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
186 double reference_value = reference_value0;
187 cont_joint->enforcePositionBounds(&reference_value);
190 double running_offset = reference_value0 - reference_value;
192 double last_value = waypoints_[0]->getJointPositions(cont_joint)[0];
193 if (running_offset > std::numeric_limits<double>::epsilon() ||
194 running_offset < -std::numeric_limits<double>::epsilon())
196 double current_value = last_value + running_offset;
197 waypoints_[0]->setJointPositions(cont_joint, ¤t_value);
200 for (std::size_t j = 1; j < waypoints_.size(); ++j)
202 double current_value = waypoints_[j]->getJointPositions(cont_joint)[0];
203 if (last_value > current_value + boost::math::constants::pi<double>())
204 running_offset += 2.0 * boost::math::constants::pi<double>();
205 else if (current_value > last_value + boost::math::constants::pi<double>())
206 running_offset -= 2.0 * boost::math::constants::pi<double>();
208 last_value = current_value;
209 if (running_offset > std::numeric_limits<double>::epsilon() ||
210 running_offset < -std::numeric_limits<double>::epsilon())
212 current_value += running_offset;
213 waypoints_[j]->setJointPositions(cont_joint, ¤t_value);
217 for (moveit::core::RobotStatePtr& waypoint : waypoints_)
223 void RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory& trajectory,
224 const std::vector<std::string>& joint_filter)
const
226 trajectory = moveit_msgs::RobotTrajectory();
227 if (waypoints_.empty())
229 const std::vector<const moveit::core::JointModel*>& jnts =
230 group_ ? group_->getActiveJointModels() : robot_model_->getActiveJointModels();
232 std::vector<const moveit::core::JointModel*> onedof;
233 std::vector<const moveit::core::JointModel*> mdof;
234 trajectory.joint_trajectory.joint_names.clear();
235 trajectory.multi_dof_joint_trajectory.joint_names.clear();
240 if (!joint_filter.empty() &&
241 std::find(joint_filter.begin(), joint_filter.end(), active_joint->getName()) == joint_filter.end())
244 if (active_joint->getVariableCount() == 1)
246 trajectory.joint_trajectory.joint_names.push_back(active_joint->getName());
247 onedof.push_back(active_joint);
251 trajectory.multi_dof_joint_trajectory.joint_names.push_back(active_joint->getName());
252 mdof.push_back(active_joint);
258 trajectory.joint_trajectory.header.frame_id = robot_model_->getModelFrame();
259 trajectory.joint_trajectory.header.stamp =
ros::Time(0);
260 trajectory.joint_trajectory.points.resize(waypoints_.size());
265 trajectory.multi_dof_joint_trajectory.header.frame_id = robot_model_->getModelFrame();
266 trajectory.multi_dof_joint_trajectory.header.stamp =
ros::Time(0);
267 trajectory.multi_dof_joint_trajectory.points.resize(waypoints_.size());
271 double total_time = 0.0;
272 for (std::size_t i = 0; i < waypoints_.size(); ++i)
274 if (duration_from_previous_.size() > i)
275 total_time += duration_from_previous_[i];
279 trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
280 trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
282 for (std::size_t j = 0; j < onedof.size(); ++j)
284 trajectory.joint_trajectory.points[i].positions[j] =
285 waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
287 if (waypoints_[i]->hasVelocities())
288 trajectory.joint_trajectory.points[i].velocities.push_back(
289 waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
290 if (waypoints_[i]->hasAccelerations())
291 trajectory.joint_trajectory.points[i].accelerations.push_back(
292 waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
293 if (waypoints_[i]->hasEffort())
294 trajectory.joint_trajectory.points[i].effort.push_back(
295 waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
298 if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
299 trajectory.joint_trajectory.points[i].velocities.clear();
301 if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
302 trajectory.joint_trajectory.points[i].accelerations.clear();
304 if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
305 trajectory.joint_trajectory.points[i].effort.clear();
307 if (duration_from_previous_.size() > i)
308 trajectory.joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
310 trajectory.joint_trajectory.points[i].time_from_start = ZERO_DURATION;
314 trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
315 for (std::size_t j = 0; j < mdof.size(); ++j)
317 geometry_msgs::TransformStamped ts =
tf2::eigenToTransform(waypoints_[i]->getJointTransform(mdof[j]));
318 trajectory.multi_dof_joint_trajectory.points[i].transforms[j] = ts.transform;
320 if (waypoints_[i]->hasVelocities() && (mdof[j]->getType() == moveit::core::JointModel::JointType::PLANAR))
322 const std::vector<std::string> names = mdof[j]->getVariableNames();
323 const double* velocities = waypoints_[i]->getJointVelocities(mdof[j]);
325 geometry_msgs::Twist point_velocity;
327 for (std::size_t k = 0; k < names.size(); ++k)
329 if (names[k].find(
"/x") != std::string::npos)
331 point_velocity.linear.x = velocities[k];
333 else if (names[k].find(
"/y") != std::string::npos)
335 point_velocity.linear.y = velocities[k];
337 else if (names[k].find(
"/z") != std::string::npos)
339 point_velocity.linear.z = velocities[k];
341 else if (names[k].find(
"/theta") != std::string::npos)
343 point_velocity.angular.z = velocities[k];
346 trajectory.multi_dof_joint_trajectory.points[i].velocities.push_back(point_velocity);
349 if (duration_from_previous_.size() > i)
350 trajectory.multi_dof_joint_trajectory.points[i].time_from_start =
ros::Duration(total_time);
352 trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ZERO_DURATION;
358 const trajectory_msgs::JointTrajectory& trajectory)
363 std::size_t state_count = trajectory.points.size();
364 ros::Time last_time_stamp = trajectory.header.stamp;
365 ros::Time this_time_stamp = last_time_stamp;
367 for (std::size_t i = 0; i < state_count; ++i)
369 this_time_stamp = trajectory.header.stamp + trajectory.points[i].time_from_start;
371 st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
372 if (!trajectory.points[i].velocities.empty())
373 st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
374 if (!trajectory.points[i].accelerations.empty())
375 st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
376 if (!trajectory.points[i].effort.empty())
377 st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
378 addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).toSec());
379 last_time_stamp = this_time_stamp;
386 const moveit_msgs::RobotTrajectory& trajectory)
392 std::size_t state_count =
393 std::max(trajectory.joint_trajectory.points.size(), trajectory.multi_dof_joint_trajectory.points.size());
394 ros::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
395 trajectory.multi_dof_joint_trajectory.header.stamp :
396 trajectory.joint_trajectory.header.stamp;
397 ros::Time this_time_stamp = last_time_stamp;
399 for (std::size_t i = 0; i < state_count; ++i)
402 if (trajectory.joint_trajectory.points.size() > i)
404 st->setVariablePositions(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].positions);
405 if (!trajectory.joint_trajectory.points[i].velocities.empty())
406 st->setVariableVelocities(trajectory.joint_trajectory.joint_names,
407 trajectory.joint_trajectory.points[i].velocities);
408 if (!trajectory.joint_trajectory.points[i].accelerations.empty())
409 st->setVariableAccelerations(trajectory.joint_trajectory.joint_names,
410 trajectory.joint_trajectory.points[i].accelerations);
411 if (!trajectory.joint_trajectory.points[i].effort.empty())
412 st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
414 trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points[i].time_from_start;
416 if (trajectory.multi_dof_joint_trajectory.points.size() > i)
418 for (std::size_t j = 0; j < trajectory.multi_dof_joint_trajectory.joint_names.size(); ++j)
420 Eigen::Isometry3d
t =
tf2::transformToEigen(trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
421 st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j],
t);
423 this_time_stamp = trajectory.multi_dof_joint_trajectory.header.stamp +
424 trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
427 addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).toSec());
428 last_time_stamp = this_time_stamp;
434 const moveit_msgs::RobotState& state,
435 const moveit_msgs::RobotTrajectory& trajectory)
439 return setRobotTrajectoryMsg(st, trajectory);
442 void RobotTrajectory::findWayPointIndicesForDurationAfterStart(
const double duration,
int& before,
int& after,
454 std::size_t
index = 0, num_points = waypoints_.size();
455 double running_duration = 0.0;
458 running_duration += duration_from_previous_[
index];
462 before = std::max<int>(index - 1, 0);
463 after = std::min<int>(index, num_points - 1);
466 double before_time = running_duration - duration_from_previous_[
index];
470 blend = (
duration - before_time) / duration_from_previous_[index];
473 double RobotTrajectory::getWayPointDurationFromStart(std::size_t index)
const
475 if (duration_from_previous_.empty())
477 if (
index >= duration_from_previous_.size())
478 index = duration_from_previous_.size() - 1;
481 for (std::size_t i = 0; i <=
index; ++i)
482 time += duration_from_previous_[i];
486 double RobotTrajectory::getWaypointDurationFromStart(std::size_t index)
const
488 return getWayPointDurationFromStart(index);
491 bool RobotTrajectory::getStateAtDurationFromStart(
const double request_duration,
492 moveit::core::RobotStatePtr& output_state)
const
495 if (getWayPointCount() == 0)
498 int before = 0, after = 0;
500 findWayPointIndicesForDurationAfterStart(request_duration, before, after, blend);
503 waypoints_[before]->interpolate(*waypoints_[after], blend, *output_state);
509 auto trajectory_length = 0.0;
514 trajectory_length += first.
distance(second);
516 return trajectory_length;