robot_trajectory.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 /* Author: Ioan Sucan, Adam Leeper */
00036 
00037 #include <moveit/robot_trajectory/robot_trajectory.h>
00038 #include <moveit/robot_state/conversions.h>
00039 #include <eigen_conversions/eigen_msg.h>
00040 #include <boost/math/constants/constants.hpp>
00041 #include <numeric>
00042 
00043 robot_trajectory::RobotTrajectory::RobotTrajectory(const robot_model::RobotModelConstPtr &kmodel, const std::string &group) :
00044   robot_model_(kmodel),
00045   group_(group.empty() ? NULL : kmodel->getJointModelGroup(group))
00046 {
00047 }
00048 
00049 void robot_trajectory::RobotTrajectory::setGroupName(const std::string &group_name)
00050 {
00051   group_ = robot_model_->getJointModelGroup(group_name);
00052 }
00053 
00054 const std::string& robot_trajectory::RobotTrajectory::getGroupName() const
00055 {
00056   if (group_)
00057     return group_->getName();
00058   static const std::string empty;
00059   return empty;
00060 }
00061 
00062 double robot_trajectory::RobotTrajectory::getAverageSegmentDuration() const
00063 {
00064   if (duration_from_previous_.empty())
00065     return 0.0;
00066   else
00067     return std::accumulate(duration_from_previous_.begin(), duration_from_previous_.end(), 0.0) / (double)duration_from_previous_.size();
00068 }
00069 
00070 void robot_trajectory::RobotTrajectory::swap(robot_trajectory::RobotTrajectory &other)
00071 {
00072   robot_model_.swap(other.robot_model_);
00073   std::swap(group_, other.group_);
00074   waypoints_.swap(other.waypoints_);
00075   duration_from_previous_.swap(other.duration_from_previous_);
00076 }
00077 
00078 void robot_trajectory::RobotTrajectory::append(const RobotTrajectory &source, double dt)
00079 {
00080   waypoints_.insert(waypoints_.end(), source.waypoints_.begin(), source.waypoints_.end());
00081   std::size_t index = duration_from_previous_.size();
00082   duration_from_previous_.insert(duration_from_previous_.end(), source.duration_from_previous_.begin(), source.duration_from_previous_.end());
00083   if (duration_from_previous_.size() > index)
00084     duration_from_previous_[index] += dt;
00085 }
00086 
00087 void robot_trajectory::RobotTrajectory::reverse()
00088 {
00089   std::reverse(waypoints_.begin(), waypoints_.end());
00090   if (!duration_from_previous_.empty())
00091   {
00092     duration_from_previous_.push_back(duration_from_previous_.front());
00093     std::reverse(duration_from_previous_.begin(), duration_from_previous_.end());
00094     duration_from_previous_.pop_back();
00095   }
00096 }
00097 
00098 void robot_trajectory::RobotTrajectory::unwind()
00099 {
00100   if (waypoints_.empty())
00101     return;
00102 
00103   const std::vector<const robot_model::JointModel*> &cont_joints = group_ ?
00104     group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
00105 
00106   for (std::size_t i = 0 ; i < cont_joints.size() ; ++i)
00107   {
00108     // unwrap continuous joints
00109     double running_offset = 0.0;
00110     double last_value = waypoints_[0]->getJointPositions(cont_joints[i])[0];
00111 
00112     for (std::size_t j = 1 ; j < waypoints_.size() ; ++j)
00113     {
00114       double current_value = waypoints_[j]->getJointPositions(cont_joints[i])[0];
00115       if (last_value > current_value + boost::math::constants::pi<double>())
00116         running_offset += 2.0 * boost::math::constants::pi<double>();
00117       else
00118         if (current_value > last_value + boost::math::constants::pi<double>())
00119           running_offset -= 2.0 * boost::math::constants::pi<double>();
00120 
00121       last_value = current_value;
00122       if (running_offset > std::numeric_limits<double>::epsilon() || running_offset < -std::numeric_limits<double>::epsilon())
00123       {
00124         current_value += running_offset;
00125         waypoints_[j]->setJointPositions(cont_joints[i], &current_value);
00126       }
00127     }
00128   }
00129   for (std::size_t j = 0 ; j < waypoints_.size() ; ++j)
00130     waypoints_[j]->update();
00131 }
00132 
00133 void robot_trajectory::RobotTrajectory::unwind(const robot_state::RobotState &state)
00134 {
00135   if (waypoints_.empty())
00136     return;
00137 
00138   const std::vector<const robot_model::JointModel*> &cont_joints = group_ ?
00139     group_->getContinuousJointModels() : robot_model_->getContinuousJointModels();
00140 
00141   for (std::size_t i = 0 ; i < cont_joints.size() ; ++i)
00142   {
00143     double reference_value0 = state.getJointPositions(cont_joints[i])[0];
00144     double reference_value = reference_value0;
00145     cont_joints[i]->enforcePositionBounds(&reference_value);
00146 
00147     // unwrap continuous joints
00148     double running_offset = reference_value0 - reference_value;
00149 
00150     double last_value = waypoints_[0]->getJointPositions(cont_joints[i])[0];
00151     if (running_offset > std::numeric_limits<double>::epsilon() || running_offset < -std::numeric_limits<double>::epsilon())
00152     {
00153       double current_value = last_value + running_offset;
00154       waypoints_[0]->setJointPositions(cont_joints[i], &current_value);
00155     }
00156 
00157     for (std::size_t j = 1 ; j < waypoints_.size() ; ++j)
00158     {
00159       double current_value = waypoints_[j]->getJointPositions(cont_joints[i])[0];
00160       if (last_value > current_value + boost::math::constants::pi<double>())
00161         running_offset += 2.0 * boost::math::constants::pi<double>();
00162       else
00163         if (current_value > last_value + boost::math::constants::pi<double>())
00164           running_offset -= 2.0 * boost::math::constants::pi<double>();
00165 
00166       last_value = current_value;
00167       if (running_offset > std::numeric_limits<double>::epsilon() || running_offset < -std::numeric_limits<double>::epsilon())
00168       {
00169         current_value += running_offset;
00170         waypoints_[j]->setJointPositions(cont_joints[i], &current_value);
00171       }
00172     }
00173   }
00174   for (std::size_t j = 0 ; j < waypoints_.size() ; ++j)
00175     waypoints_[j]->update();
00176 }
00177 
00178 void robot_trajectory::RobotTrajectory::clear()
00179 {
00180   waypoints_.clear();
00181   duration_from_previous_.clear();
00182 }
00183 
00184 void robot_trajectory::RobotTrajectory::getRobotTrajectoryMsg(moveit_msgs::RobotTrajectory &trajectory) const
00185 {
00186   trajectory = moveit_msgs::RobotTrajectory();
00187   if (waypoints_.empty())
00188     return;
00189   const std::vector<const robot_model::JointModel*> &jnt = group_ ? group_->getActiveJointModels() : robot_model_->getActiveJointModels();
00190 
00191   std::vector<const robot_model::JointModel*> onedof;
00192   std::vector<const robot_model::JointModel*> mdof;
00193   trajectory.joint_trajectory.joint_names.clear();
00194   trajectory.multi_dof_joint_trajectory.joint_names.clear();
00195 
00196   for (std::size_t i = 0 ; i < jnt.size() ; ++i)
00197     if (jnt[i]->getVariableCount() == 1)
00198     {
00199       trajectory.joint_trajectory.joint_names.push_back(jnt[i]->getName());
00200       onedof.push_back(jnt[i]);
00201     }
00202     else
00203     {
00204       trajectory.multi_dof_joint_trajectory.joint_names.push_back(jnt[i]->getName());
00205       mdof.push_back(jnt[i]);
00206     }
00207   if (!onedof.empty())
00208   {
00209     trajectory.joint_trajectory.header.frame_id = robot_model_->getModelFrame();
00210     trajectory.joint_trajectory.header.stamp = ros::Time(0);
00211     trajectory.joint_trajectory.points.resize(waypoints_.size());
00212   }
00213 
00214   if (!mdof.empty())
00215   {
00216     trajectory.multi_dof_joint_trajectory.header.frame_id = robot_model_->getModelFrame();
00217     trajectory.multi_dof_joint_trajectory.header.stamp = ros::Time(0);
00218     trajectory.multi_dof_joint_trajectory.points.resize(waypoints_.size());
00219   }
00220 
00221   static const ros::Duration zero_duration(0.0);
00222   double total_time = 0.0;
00223   for (std::size_t i = 0 ; i < waypoints_.size() ; ++i)
00224   {
00225     if (duration_from_previous_.size() > i)
00226       total_time += duration_from_previous_[i];
00227 
00228     if (!onedof.empty())
00229     {
00230       trajectory.joint_trajectory.points[i].positions.resize(onedof.size());
00231       trajectory.joint_trajectory.points[i].velocities.reserve(onedof.size());
00232 
00233       for (std::size_t j = 0 ; j < onedof.size() ; ++j)
00234       {
00235         trajectory.joint_trajectory.points[i].positions[j] = waypoints_[i]->getVariablePosition(onedof[j]->getFirstVariableIndex());
00236         // if we have velocities/accelerations/effort, copy those too
00237         if (waypoints_[i]->hasVelocities())
00238           trajectory.joint_trajectory.points[i].velocities.push_back(waypoints_[i]->getVariableVelocity(onedof[j]->getFirstVariableIndex()));
00239         if (waypoints_[i]->hasAccelerations())
00240           trajectory.joint_trajectory.points[i].accelerations.push_back(waypoints_[i]->getVariableAcceleration(onedof[j]->getFirstVariableIndex()));
00241         if (waypoints_[i]->hasEffort())
00242           trajectory.joint_trajectory.points[i].effort.push_back(waypoints_[i]->getVariableEffort(onedof[j]->getFirstVariableIndex()));
00243       }
00244       // clear velocities if we have an incomplete specification
00245       if (trajectory.joint_trajectory.points[i].velocities.size() != onedof.size())
00246         trajectory.joint_trajectory.points[i].velocities.clear();
00247       // clear accelerations if we have an incomplete specification
00248       if (trajectory.joint_trajectory.points[i].accelerations.size() != onedof.size())
00249         trajectory.joint_trajectory.points[i].accelerations.clear();
00250       // clear effort if we have an incomplete specification
00251       if (trajectory.joint_trajectory.points[i].effort.size() != onedof.size())
00252         trajectory.joint_trajectory.points[i].effort.clear();
00253 
00254       if (duration_from_previous_.size() > i)
00255         trajectory.joint_trajectory.points[i].time_from_start = ros::Duration(total_time);
00256       else
00257         trajectory.joint_trajectory.points[i].time_from_start = zero_duration;
00258     }
00259     if (!mdof.empty())
00260     {
00261       trajectory.multi_dof_joint_trajectory.points[i].transforms.resize(mdof.size());
00262       for (std::size_t j = 0 ; j < mdof.size() ; ++j)
00263         tf::transformEigenToMsg(waypoints_[i]->getJointTransform(mdof[j]),
00264                                 trajectory.multi_dof_joint_trajectory.points[i].transforms[j]);
00265       if (duration_from_previous_.size() > i)
00266         trajectory.multi_dof_joint_trajectory.points[i].time_from_start = ros::Duration(total_time);
00267       else
00268         trajectory.multi_dof_joint_trajectory.points[i].time_from_start = zero_duration;
00269     }
00270   }
00271 }
00272 
00273 void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg(const robot_state::RobotState &reference_state,
00274                                                               const trajectory_msgs::JointTrajectory &trajectory)
00275 {
00276   // make a copy just in case the next clear() removes the memory for the reference passed in
00277   robot_state::RobotState copy = reference_state;
00278   clear();
00279   std::size_t state_count = trajectory.points.size();
00280   ros::Time last_time_stamp = trajectory.header.stamp;
00281   ros::Time this_time_stamp = last_time_stamp;
00282   
00283   for (std::size_t i = 0 ; i < state_count ; ++i)
00284   {
00285     this_time_stamp = trajectory.header.stamp + trajectory.points[i].time_from_start;
00286     robot_state::RobotStatePtr st(new robot_state::RobotState(copy));
00287     st->setVariablePositions(trajectory.joint_names, trajectory.points[i].positions);
00288     if (!trajectory.points[i].velocities.empty())
00289       st->setVariableVelocities(trajectory.joint_names, trajectory.points[i].velocities);
00290     if (!trajectory.points[i].accelerations.empty())
00291       st->setVariableAccelerations(trajectory.joint_names, trajectory.points[i].accelerations);
00292     if (!trajectory.points[i].effort.empty())
00293       st->setVariableEffort(trajectory.joint_names, trajectory.points[i].effort);
00294     addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).toSec());
00295     last_time_stamp = this_time_stamp;
00296   }
00297 }
00298 
00299 void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg(const robot_state::RobotState &reference_state,
00300                                                               const moveit_msgs::RobotTrajectory &trajectory)
00301 {
00302   // make a copy just in case the next clear() removes the memory for the reference passed in
00303   robot_state::RobotState copy = reference_state;
00304   clear();
00305   
00306   std::size_t state_count = std::max(trajectory.joint_trajectory.points.size(),
00307                                      trajectory.multi_dof_joint_trajectory.points.size());
00308   ros::Time last_time_stamp = trajectory.joint_trajectory.points.empty() ?
00309     trajectory.multi_dof_joint_trajectory.header.stamp : trajectory.joint_trajectory.header.stamp;
00310   ros::Time this_time_stamp = last_time_stamp;
00311   
00312   for (std::size_t i = 0 ; i < state_count ; ++i)
00313   {
00314     robot_state::RobotStatePtr st(new robot_state::RobotState(copy));
00315     if (trajectory.joint_trajectory.points.size() > i)
00316     {
00317       st->setVariablePositions(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].positions);
00318       if (!trajectory.joint_trajectory.points[i].velocities.empty())
00319         st->setVariableVelocities(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].velocities);
00320       if (!trajectory.joint_trajectory.points[i].accelerations.empty())
00321         st->setVariableAccelerations(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].accelerations);
00322       if (!trajectory.joint_trajectory.points[i].effort.empty())
00323         st->setVariableEffort(trajectory.joint_trajectory.joint_names, trajectory.joint_trajectory.points[i].effort);
00324       this_time_stamp = trajectory.joint_trajectory.header.stamp + trajectory.joint_trajectory.points[i].time_from_start;
00325     }
00326     if (trajectory.multi_dof_joint_trajectory.points.size() > i)
00327     {
00328       for (std::size_t j = 0 ; j < trajectory.multi_dof_joint_trajectory.joint_names.size() ; ++j)
00329       {
00330         Eigen::Affine3d t;
00331         tf::transformMsgToEigen(trajectory.multi_dof_joint_trajectory.points[i].transforms[j], t);
00332         st->setJointPositions(trajectory.multi_dof_joint_trajectory.joint_names[j], t);
00333       }
00334       this_time_stamp = trajectory.multi_dof_joint_trajectory.header.stamp + trajectory.multi_dof_joint_trajectory.points[i].time_from_start;
00335     }
00336     
00337     addSuffixWayPoint(st, (this_time_stamp - last_time_stamp).toSec());
00338     last_time_stamp = this_time_stamp;
00339   }
00340 }
00341 
00342 void robot_trajectory::RobotTrajectory::setRobotTrajectoryMsg(const robot_state::RobotState &reference_state,
00343                                                               const moveit_msgs::RobotState &state, const moveit_msgs::RobotTrajectory &trajectory)
00344 {
00345   robot_state::RobotState st(reference_state);
00346   robot_state::robotStateMsgToRobotState(state, st);
00347   setRobotTrajectoryMsg(st, trajectory);
00348 }
00349 
00350 void robot_trajectory::RobotTrajectory::findWayPointIndicesForDurationAfterStart(const double& duration, int& before, int& after, double &blend) const
00351 {
00352   if (duration < 0.0)
00353   {
00354     before = 0;
00355     after = 0;
00356     blend = 0;
00357     return;
00358   }
00359 
00360   // Find indicies
00361   std::size_t index = 0, num_points = waypoints_.size();
00362   double running_duration = 0.0;
00363   for ( ; index < num_points; ++index)
00364   {
00365     running_duration += duration_from_previous_[index];
00366     if (running_duration >= duration)
00367       break;
00368   }
00369   before = std::max<int>(index - 1, 0);
00370   after = std::min<int>(index, num_points - 1);
00371 
00372   // Compute duration blend
00373   double before_time = running_duration - duration_from_previous_[index];
00374   if (after == before)
00375     blend = 1.0;
00376   else
00377     blend = (duration - before_time) / duration_from_previous_[index];
00378 }
00379 
00380 double robot_trajectory::RobotTrajectory::getWaypointDurationFromStart(std::size_t index) const
00381 {
00382   if (duration_from_previous_.empty())
00383     return 0.0;
00384   if (index >= duration_from_previous_.size())
00385     index = duration_from_previous_.size() - 1;
00386   
00387   double time = 0.0;
00388   for (std::size_t i = 0; i <= index; ++i)
00389     time += duration_from_previous_[i];
00390   return time;
00391 }
00392 
00393 bool robot_trajectory::RobotTrajectory::getStateAtDurationFromStart(const double request_duration, robot_state::RobotStatePtr& output_state) const
00394 {
00395   if (!getWayPointCount())
00396     return false;
00397 
00398   int before = 0, after = 0;
00399   double blend = 1.0;
00400   findWayPointIndicesForDurationAfterStart(request_duration, before, after, blend);
00401   //logDebug("Interpolating %.3f of the way between index %d and %d.", blend, before, after);
00402   waypoints_[before]->interpolate(*waypoints_[after], blend, *output_state);
00403   return true;
00404 }


moveit_core
Author(s): Ioan Sucan , Sachin Chitta , Acorn Pooley
autogenerated on Thu Aug 27 2015 13:58:53