follow_joint_trajectory.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  *  Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014-2015, Fetch Robotics Inc.
00005  *  Copyright (c) 2013, Unbounded Robotics Inc.
00006  *  All rights reserved.
00007  *
00008  *  Redistribution and use in source and binary forms, with or without
00009  *  modification, are permitted provided that the following conditions
00010  *  are met:
00011  *
00012  *   * Redistributions of source code must retain the above copyright
00013  *     notice, this list of conditions and the following disclaimer.
00014  *   * Redistributions in binary form must reproduce the above
00015  *     copyright notice, this list of conditions and the following
00016  *     disclaimer in the documentation and/or other materials provided
00017  *     with the distribution.
00018  *   * Neither the name of Unbounded Robotics nor the names of its
00019  *     contributors may be used to endorse or promote products derived
00020  *     from this software without specific prior written permission.
00021  *
00022  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033  *  POSSIBILITY OF SUCH DAMAGE.
00034  *********************************************************************/
00035 
00036 /* Author: Michael Ferguson */
00037 
00038 #include <pluginlib/class_list_macros.h>
00039 #include <robot_controllers/follow_joint_trajectory.h>
00040 
00041 using angles::shortest_angular_distance;
00042 
00043 PLUGINLIB_EXPORT_CLASS(robot_controllers::FollowJointTrajectoryController, robot_controllers::Controller)
00044 
00045 namespace robot_controllers
00046 {
00047 
00048 FollowJointTrajectoryController::FollowJointTrajectoryController() :
00049     initialized_(false)
00050 {
00051 }
00052 
00053 int FollowJointTrajectoryController::init(ros::NodeHandle& nh, ControllerManager* manager)
00054 {
00055   // We absolutely need access to the controller manager
00056   if (!manager)
00057   {
00058     initialized_ = false;
00059     return -1;
00060   }
00061 
00062   Controller::init(nh, manager);
00063   manager_ = manager;
00064 
00065   // No initial sampler
00066   boost::mutex::scoped_lock lock(sampler_mutex_);
00067   sampler_.reset();
00068   preempted_ = false;
00069 
00070   // Get Joint Names
00071   joint_names_.clear();
00072   XmlRpc::XmlRpcValue names;
00073   if (!nh.getParam("joints", names))
00074   {
00075     ROS_ERROR_STREAM("No joints given for " << nh.getNamespace());
00076     return -1;
00077   }
00078   if (names.getType() != XmlRpc::XmlRpcValue::TypeArray)
00079   {
00080     ROS_ERROR_STREAM("Joints not in a list for " << nh.getNamespace());
00081     return -1;
00082   }
00083   for (int i = 0; i < names.size(); ++i)
00084   {
00085     XmlRpc::XmlRpcValue &name_value = names[i];
00086     if (name_value.getType() != XmlRpc::XmlRpcValue::TypeString)
00087     {
00088       ROS_ERROR_STREAM("Not all joint names are strings for " << nh.getNamespace());
00089       return -1;
00090     }
00091     joint_names_.push_back(static_cast<std::string>(name_value));
00092   }
00093 
00094   // Get parameters
00095   nh.param<bool>("stop_with_action", stop_with_action_, false);
00096   nh.param<bool>("stop_on_path_violation", stop_on_path_violation_, false);
00097 
00098   // Get Joint Handles, setup feedback
00099   joints_.clear();
00100   for (size_t i = 0; i < joint_names_.size(); ++i)
00101   {
00102     JointHandlePtr j = manager_->getJointHandle(joint_names_[i]);
00103     feedback_.joint_names.push_back(j->getName());
00104     joints_.push_back(j);
00105     continuous_.push_back(j->isContinuous());
00106   }
00107 
00108   // Update feedback
00109   feedback_.desired.positions.resize(joints_.size());
00110   feedback_.desired.velocities.resize(joints_.size());
00111   feedback_.desired.accelerations.resize(joints_.size());
00112   feedback_.actual.positions.resize(joints_.size());
00113   feedback_.actual.velocities.resize(joints_.size());
00114   feedback_.actual.effort.resize(joints_.size());
00115   feedback_.error.positions.resize(joints_.size());
00116   feedback_.error.velocities.resize(joints_.size());
00117 
00118   // Update tolerances
00119   path_tolerance_.q.resize(joints_.size());
00120   path_tolerance_.qd.resize(joints_.size());
00121   path_tolerance_.qdd.resize(joints_.size());
00122   goal_tolerance_.q.resize(joints_.size());
00123   goal_tolerance_.qd.resize(joints_.size());
00124   goal_tolerance_.qdd.resize(joints_.size()); 
00125 
00126   // Setup ROS interfaces
00127   server_.reset(new server_t(nh, "",
00128                              boost::bind(&FollowJointTrajectoryController::executeCb, this, _1),
00129                              false));
00130   server_->start();
00131 
00132   initialized_ = true;
00133   return 0;
00134 }
00135 
00136 bool FollowJointTrajectoryController::start()
00137 {
00138   if (!initialized_)
00139   {
00140     ROS_ERROR_NAMED("FollowJointTrajectoryController",
00141                     "Unable to start, not initialized.");
00142     return false;
00143   }
00144 
00145   if (!server_->isActive())
00146   {
00147     ROS_ERROR_NAMED("FollowJointTrajectoryController",
00148                     "Unable to start, action server is not active.");
00149     return false;
00150   }
00151 
00152   return true;
00153 }
00154 
00155 bool FollowJointTrajectoryController::stop(bool force)
00156 {
00157   if (!initialized_)
00158     return true;
00159 
00160   if (server_->isActive())
00161   {
00162     if (force)
00163     {
00164       // Shut down the action
00165       control_msgs::FollowJointTrajectoryResult result;
00166       server_->setAborted(result, "Controller manager forced preemption.");
00167       return true;
00168     }
00169     // Do not abort unless forced
00170     return false;
00171   }
00172 
00173   // Just holding position, go ahead and stop us
00174   return true;
00175 }
00176 
00177 bool FollowJointTrajectoryController::reset()
00178 {
00179   stop(true);  // force stop ourselves
00180   return (manager_->requestStop(getName()) == 0);
00181 }
00182 
00183 void FollowJointTrajectoryController::update(const ros::Time& now, const ros::Duration& dt)
00184 {
00185   if (!initialized_)
00186     return;
00187 
00188   // Is trajectory active?
00189   if (server_->isActive() && sampler_)
00190   {
00191     boost::mutex::scoped_lock lock(sampler_mutex_);
00192 
00193     // Interpolate trajectory
00194     TrajectoryPoint p = sampler_->sample(now.toSec());
00195     unwindTrajectoryPoint(continuous_, p);
00196     last_sample_ = p;
00197 
00198     // Update joints
00199     if (p.q.size() == joints_.size())
00200     {
00201       // Position is good
00202       for (size_t i = 0; i < joints_.size(); ++i)
00203       {
00204         feedback_.desired.positions[i] = p.q[i];
00205       }
00206 
00207       if (p.qd.size() == joints_.size())
00208       {
00209         // Velocity is good
00210         for (size_t i = 0; i < joints_.size(); ++i)
00211         {
00212           feedback_.desired.velocities[i] = p.qd[i];
00213         }
00214 
00215         if (p.qdd.size() == joints_.size())
00216         {
00217           // Acceleration is good
00218           for (size_t i = 0; i < joints_.size(); ++i)
00219           {
00220             feedback_.desired.accelerations[i] = p.qdd[i];
00221           }
00222         }
00223       }
00224 
00225       // Fill in actual
00226       for (size_t j = 0; j < joints_.size(); ++j)
00227       {
00228         feedback_.actual.positions[j] = joints_[j]->getPosition();
00229         feedback_.actual.velocities[j] = joints_[j]->getVelocity();
00230         feedback_.actual.effort[j] = joints_[j]->getEffort();
00231       }
00232 
00233       // Fill in error
00234       for (size_t j = 0; j < joints_.size(); ++j)
00235       {
00236         feedback_.error.positions[j] = shortest_angular_distance(feedback_.desired.positions[j],
00237                                                                  feedback_.actual.positions[j]);
00238         feedback_.error.velocities[j] = feedback_.actual.velocities[j] -
00239                                         feedback_.desired.velocities[j];
00240       }
00241 
00242       // Check that we are within path tolerance
00243       if (has_path_tolerance_)
00244       {
00245         for (size_t j = 0; j < joints_.size(); ++j)
00246         {
00247           if ((path_tolerance_.q[j] > 0) &&
00248               (fabs(feedback_.error.positions[j]) > path_tolerance_.q[j]))
00249           {
00250             control_msgs::FollowJointTrajectoryResult result;
00251             result.error_code = control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
00252             server_->setAborted(result, "Trajectory path tolerances violated (position).");
00253             ROS_ERROR("Trajectory path tolerances violated (position).");
00254             if (stop_on_path_violation_)
00255             {
00256               manager_->requestStop(getName());
00257             }
00258             break;
00259           }
00260 
00261           if ((path_tolerance_.qd[j] > 0) &&
00262               (fabs(feedback_.error.velocities[j]) > path_tolerance_.qd[j]))
00263           {
00264             control_msgs::FollowJointTrajectoryResult result;
00265             result.error_code = control_msgs::FollowJointTrajectoryResult::PATH_TOLERANCE_VIOLATED;
00266             server_->setAborted(result, "Trajectory path tolerances violated (velocity).");
00267             ROS_ERROR("Trajectory path tolerances violated (velocity).");
00268             if (stop_on_path_violation_)
00269             {
00270               manager_->requestStop(getName());
00271             }
00272             break;
00273           }
00274         }
00275       }
00276 
00277       // Check that we are within goal tolerance
00278       if (now.toSec() >= sampler_->end_time())
00279       {
00280         bool inside_tolerances = true;
00281         for (size_t j = 0; j < joints_.size(); ++j)
00282         {
00283           if ((goal_tolerance_.q[j] > 0) &&
00284               (fabs(feedback_.error.positions[j]) > goal_tolerance_.q[j]))
00285           {
00286             inside_tolerances = false;
00287           }
00288         }
00289 
00290         if (inside_tolerances)
00291         {
00292           control_msgs::FollowJointTrajectoryResult result;
00293           result.error_code = control_msgs::FollowJointTrajectoryResult::SUCCESSFUL;
00294           server_->setSucceeded(result, "Trajectory succeeded.");
00295           ROS_DEBUG("Trajectory succeeded");
00296         }
00297         else if (now.toSec() > (sampler_->end_time() + goal_time_tolerance_ + 0.6))  // 0.6s matches PR2
00298         {
00299           control_msgs::FollowJointTrajectoryResult result;
00300           result.error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
00301           server_->setAborted(result, "Trajectory not executed within time limits.");
00302           ROS_ERROR("Trajectory not executed within time limits");
00303         }
00304       }
00305 
00306       // Update joints
00307       for (size_t j = 0; j < joints_.size(); ++j)
00308       {
00309         joints_[j]->setPosition(feedback_.desired.positions[j],
00310                                 feedback_.desired.velocities[j],
00311                                 0.0);
00312       }
00313     }
00314   }
00315   else if (last_sample_.q.size() == joints_.size())
00316   {
00317     // Hold Position Unless Path Tolerance Violated
00318     if (has_path_tolerance_ && stop_on_path_violation_)
00319     {
00320       for (size_t j = 0; j < joints_.size(); ++j)
00321       {
00322         if ((path_tolerance_.q[j] > 0) &&
00323             (fabs(joints_[j]->getPosition() - last_sample_.q[j]) > path_tolerance_.q[j]))
00324         {
00325           manager_->requestStop(getName());
00326           break;
00327         }
00328       }
00329     }
00330 
00331     for (size_t j = 0; j < joints_.size(); ++j)
00332     {
00333       joints_[j]->setPosition(last_sample_.q[j],
00334                               0.0,
00335                               0.0);
00336     }
00337   }
00338 }
00339 
00340 /*
00341  * Specification is basically the message:
00342  * http://ros.org/doc/indigo/api/control_msgs/html/action/FollowJointTrajectory.html
00343  */
00344 void FollowJointTrajectoryController::executeCb(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal)
00345 {
00346   control_msgs::FollowJointTrajectoryResult result;
00347 
00348   if (!initialized_)
00349   {
00350     server_->setAborted(result, "Controller is not initialized.");
00351     return;
00352   }
00353 
00354   if (goal->trajectory.points.empty())
00355   {
00356     // Stop
00357     manager_->requestStop(getName());
00358     return;
00359   }
00360 
00361   if (goal->trajectory.joint_names.size() != joints_.size())
00362   {
00363     result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00364     server_->setAborted(result, "Trajectory goal size does not match controlled joints size.");
00365     ROS_ERROR("Trajectory goal size does not match controlled joints size.");
00366     return;
00367   }
00368 
00369   Trajectory new_trajectory;
00370   Trajectory executable_trajectory;
00371 
00372   // Make a trajectory from our message
00373   if (!trajectoryFromMsg(goal->trajectory, joint_names_, &new_trajectory))
00374   {
00375     result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00376     server_->setAborted(result, "Trajectory goal does not match controlled joints");
00377     ROS_ERROR("Trajectory goal does not match controlled joints");
00378     return;
00379   }
00380 
00381   // If preempted, need to splice on things together
00382   if (preempted_)
00383   {
00384     // If the sampler had a large trajectory, we may just be cutting into it
00385     if (sampler_ && (sampler_->getTrajectory().size() > 2))
00386     {
00387       if (!spliceTrajectories(sampler_->getTrajectory(),
00388                               new_trajectory,
00389                               ros::Time::now().toSec(),
00390                               &executable_trajectory))
00391       {
00392         result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00393         server_->setAborted(result, "Unable to splice trajectory");
00394         ROS_ERROR("Unable to splice trajectory");
00395         return;
00396       }
00397     }
00398     else
00399     {
00400       // Previous trajectory was only 2 points, use last_sample + new trajectory
00401       Trajectory t;
00402       t.points.push_back(last_sample_);
00403       if (!spliceTrajectories(t,
00404                               new_trajectory,
00405                               0.0, /* take all points */
00406                               &executable_trajectory))
00407       {
00408         result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00409         server_->setAborted(result, "Unable to splice trajectory");
00410         ROS_ERROR("Unable to splice trajectory");
00411         return;
00412       }
00413     }
00414   }
00415   else
00416   {
00417     if (new_trajectory.size() > 1)
00418     {
00419       // use the generated trajectory
00420       executable_trajectory = new_trajectory;
00421 
00422       // if this hasn't started yet, need to insert current position
00423       if (goal->trajectory.points[0].time_from_start.toSec() > 0.0)
00424       {
00425         executable_trajectory.points.insert(
00426           executable_trajectory.points.begin(),
00427           getPointFromCurrent(new_trajectory.points[0].qd.size() > 0,
00428                               new_trajectory.points[0].qdd.size() > 0,
00429                               true));
00430       }
00431     }
00432     else
00433     {
00434       // A single point, with nothing in the queue!
00435       executable_trajectory.points.push_back(
00436           getPointFromCurrent(new_trajectory.points[0].qd.size() > 0,
00437                               new_trajectory.points[0].qdd.size() > 0,
00438                               true));
00439       executable_trajectory.points.push_back(new_trajectory.points[0]);
00440     }
00441   }
00442 
00443   // Windup executable trajectory so spline is smooth
00444   windupTrajectory(continuous_, executable_trajectory);
00445 
00446   // Create trajectory sampler
00447   {
00448     boost::mutex::scoped_lock lock(sampler_mutex_);
00449     sampler_.reset(new SplineTrajectorySampler(executable_trajectory));
00450   }
00451 
00452   // Convert the path tolerances into a more usable form
00453   if (goal->path_tolerance.size() == joints_.size())
00454   {
00455     has_path_tolerance_ = true;
00456     for (size_t j = 0; j < joints_.size(); ++j)
00457     {
00458       // Find corresponding indices between path_tolerance and joints
00459       int index = -1;
00460       for (size_t i = 0; i < goal->path_tolerance.size(); ++i)
00461       {
00462         if (joints_[j]->getName() == goal->path_tolerance[i].name)
00463         {
00464           index = i;
00465           break;
00466         }
00467       }
00468       if (index == -1)
00469       {
00470         // Every joint must have a tolerance and this one does not
00471         result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00472         server_->setAborted(result, "Unable to convert path tolerances");
00473         ROS_ERROR("Unable to convert path tolerances");
00474         return;
00475       }
00476       path_tolerance_.q[j] = goal->path_tolerance[index].position;
00477       path_tolerance_.qd[j] = goal->path_tolerance[index].velocity;
00478       path_tolerance_.qdd[j] = goal->path_tolerance[index].acceleration;
00479     }
00480   }
00481   else
00482   {
00483     has_path_tolerance_ = false;
00484   }
00485 
00486   // Convert the goal tolerances into a more usable form
00487   if (goal->goal_tolerance.size() == joints_.size())
00488   {
00489     for (size_t j = 0; j < joints_.size(); ++j)
00490     {
00491       // Find corresponding indices between goal_tolerance and joints
00492       int index = -1;
00493       for (size_t i = 0; i < goal->goal_tolerance.size(); ++i)
00494       {
00495         if (joints_[j]->getName() == goal->goal_tolerance[i].name)
00496         {
00497           index = i;
00498           break;
00499         }
00500       }
00501       if (index == -1)
00502       {
00503         // Every joint must have a tolerance and this one does not
00504         result.error_code = control_msgs::FollowJointTrajectoryResult::INVALID_JOINTS;
00505         server_->setAborted(result, "Unable to convert goal tolerances");
00506         ROS_ERROR("Unable to convert goal tolerances");
00507         return;
00508       }
00509       goal_tolerance_.q[j] = goal->goal_tolerance[index].position;
00510       goal_tolerance_.qd[j] = goal->goal_tolerance[index].velocity;
00511       goal_tolerance_.qdd[j] = goal->goal_tolerance[index].acceleration;
00512     }
00513   }
00514   else
00515   {
00516     // Set defaults
00517     for (size_t j = 0; j < joints_.size(); ++j)
00518     {
00519       goal_tolerance_.q[j] = 0.02;  // tolerance is same as PR2
00520       goal_tolerance_.qd[j] = 0.02;
00521       goal_tolerance_.qdd[j] = 0.02;
00522     }
00523   }
00524   goal_time_tolerance_ = goal->goal_time_tolerance.toSec();
00525 
00526   ROS_DEBUG("Executing new trajectory");
00527 
00528   if (manager_->requestStart(getName()) != 0)
00529   {
00530     result.error_code = control_msgs::FollowJointTrajectoryResult::GOAL_TOLERANCE_VIOLATED;
00531     server_->setAborted(result, "Cannot execute trajectory, unable to start controller.");
00532     ROS_ERROR("Cannot execute trajectory, unable to start controller.");
00533     return;
00534   }
00535 
00536   preempted_ = false;
00537   while (server_->isActive())
00538   {
00539     if (server_->isPreemptRequested())
00540     {
00541       control_msgs::FollowJointTrajectoryResult result;
00542       server_->setPreempted(result, "Trajectory preempted");
00543       ROS_DEBUG("Trajectory preempted");
00544       preempted_ = true;
00545       break;
00546     }
00547 
00548     // Publish feedback
00549     feedback_.header.stamp = ros::Time::now();
00550     server_->publishFeedback(feedback_);
00551     ros::Duration(1/50.0).sleep();
00552   }
00553 
00554   {
00555     boost::mutex::scoped_lock lock(sampler_mutex_);
00556     sampler_.reset();
00557   }
00558 
00559   // Stop this controller if desired (and not preempted)
00560   if (stop_with_action_ && !preempted_)
00561     manager_->requestStop(getName());
00562 
00563   ROS_DEBUG("Done executing trajectory");
00564 }
00565 
00566 TrajectoryPoint FollowJointTrajectoryController::getPointFromCurrent(
00567   bool incl_vel, bool incl_acc, bool zero_vel)
00568 {
00569   TrajectoryPoint point;
00570 
00571   point.q.resize(joints_.size());
00572   for (size_t j = 0; j < joints_.size(); ++j)
00573     point.q[j] = joints_[j]->getPosition();
00574 
00575   if (incl_vel && zero_vel)
00576   {
00577     point.qd.resize(joints_.size());
00578     for (size_t j = 0; j < joints_.size(); ++j)
00579       point.qd[j] = 0.0;
00580   }
00581   else if (incl_vel)
00582   {
00583     point.qd.resize(joints_.size());
00584     for (size_t j = 0; j < joints_.size(); ++j)
00585       point.qd[j] = joints_[j]->getVelocity();
00586   }
00587 
00588   if (incl_acc)
00589   {
00590     point.qdd.resize(joints_.size());
00591     // Currently no good measure of acceleration, assume none
00592     for (size_t j = 0; j < joints_.size(); ++j)
00593       point.qdd[j] = 0.0;
00594   }
00595 
00596   point.time = ros::Time::now().toSec();
00597 
00598   return point;
00599 }
00600 
00601 std::vector<std::string> FollowJointTrajectoryController::getCommandedNames()
00602 {
00603   return joint_names_;
00604 }
00605 
00606 std::vector<std::string> FollowJointTrajectoryController::getClaimedNames()
00607 {
00608   return joint_names_;
00609 }
00610 
00611 }  // namespace robot_controllers


robot_controllers
Author(s): Michael Ferguson
autogenerated on Wed Jun 14 2017 04:09:10