follow_joint_trajectory.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  *  Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2014, 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 #ifndef ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H
00039 #define ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H
00040 
00041 #include <string>
00042 #include <vector>
00043 #include <boost/shared_ptr.hpp>
00044 #include <boost/thread.hpp>
00045 
00046 #include <ros/ros.h>
00047 #include <robot_controllers_interface/controller.h>
00048 #include <robot_controllers_interface/joint_handle.h>
00049 #include <robot_controllers_interface/controller_manager.h>
00050 #include <control_msgs/FollowJointTrajectoryAction.h>
00051 #include <actionlib/server/simple_action_server.h>
00052 
00053 #include <angles/angles.h>
00054 #include <robot_controllers/trajectory.h>
00055 #include <robot_controllers/trajectory_spline_sampler.h>
00056 
00057 namespace robot_controllers
00058 {
00059 
00065 class FollowJointTrajectoryController : public Controller
00066 {
00067   typedef actionlib::SimpleActionServer<control_msgs::FollowJointTrajectoryAction> server_t;
00068 
00069 public:
00070   FollowJointTrajectoryController();
00071   virtual ~FollowJointTrajectoryController() {}
00072 
00080   virtual int init(ros::NodeHandle& nh, ControllerManager* manager);
00081 
00087   virtual bool start();
00088 
00096   virtual bool stop(bool force);
00097 
00104   virtual bool reset();
00105 
00111   virtual void update(const ros::Time& now, const ros::Duration& dt);
00112 
00114   virtual std::string getType()
00115   {
00116     return "robot_controllers/FollowJointTrajectoryController";
00117   }
00118 
00120   virtual std::vector<std::string> getCommandedNames();
00121 
00123   virtual std::vector<std::string> getClaimedNames();
00124 
00125 private:
00127   void executeCb(const control_msgs::FollowJointTrajectoryGoalConstPtr& goal);
00128 
00130   TrajectoryPoint getPointFromCurrent(bool incl_vel, bool incl_acc, bool zero_vel);
00131 
00132   bool initialized_;
00133   ControllerManager* manager_;
00134 
00135   std::vector<JointHandlePtr> joints_;
00136   std::vector<std::string> joint_names_;
00137   std::vector<bool> continuous_;
00138   boost::shared_ptr<server_t> server_;
00139 
00140   boost::shared_ptr<TrajectorySampler> sampler_;
00141   boost::mutex sampler_mutex_;
00142 
00143   bool stop_with_action_;  
00144 
00145 
00146   bool stop_on_path_violation_;  
00147 
00148 
00149   /*
00150    * In certain cases, we want to start a trajectory at our last sample,
00151    * for instance if we were pre-empted (as is often the case with teleop)
00152    * we need to use the velocity and position of the last sample as a
00153    * starting point.
00154    */
00155   TrajectoryPoint last_sample_;
00156   bool preempted_;  
00157 
00158   bool has_path_tolerance_;
00159   TrajectoryPoint path_tolerance_;
00160 
00161   bool has_goal_tolerance_;
00162   TrajectoryPoint goal_tolerance_;
00163   double goal_time_tolerance_;
00164 
00165   control_msgs::FollowJointTrajectoryFeedback feedback_;
00166 };
00167 
00168 }  // namespace robot_controllers
00169 
00170 #endif  // ROBOT_CONTROLLERS_FOLLOW_JOINT_TRAJECTORY_H_


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