joint_spline_trajectory_controller.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  */
00029 
00037 #ifndef JOINT_TRAJECTORY_CONTROLLER_H__
00038 #define JOINT_TRAJECTORY_CONTROLLER_H__
00039 
00040 #include <vector>
00041 
00042 #include <boost/scoped_ptr.hpp>
00043 #include <boost/thread/recursive_mutex.hpp>
00044 #include <boost/thread/condition.hpp>
00045 #include <ros/node_handle.h>
00046 #include <control_toolbox/pid.h>
00047 #include <pr2_controller_interface/controller.h>
00048 #include <realtime_tools/realtime_publisher.h>
00049 #include <realtime_tools/realtime_box.h>
00050 
00051 #include "trajectory_msgs/JointTrajectory.h"
00052 //#include "robot_mechanism_controllers/Trajectory.h"
00053 #include "pr2_controllers_msgs/QueryTrajectoryState.h"
00054 #include "pr2_controllers_msgs/JointTrajectoryControllerState.h"
00055 
00056 namespace controller {
00057 
00058 class JointSplineTrajectoryController : public pr2_controller_interface::Controller
00059 {
00060 public:
00061 
00062   JointSplineTrajectoryController();
00063   ~JointSplineTrajectoryController();
00064 
00065   bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n);
00066 
00067   void starting();
00068   void update();
00069 
00070 private:
00071   int loop_count_;
00072   pr2_mechanism_model::RobotState *robot_;
00073   ros::Time last_time_;
00074   std::vector<pr2_mechanism_model::JointState*> joints_;
00075   std::vector<control_toolbox::Pid> pids_;
00076 
00077   ros::NodeHandle node_;
00078 
00079   void commandCB(const trajectory_msgs::JointTrajectoryConstPtr &msg);
00080   ros::Subscriber sub_command_;
00081 
00082   bool queryStateService(pr2_controllers_msgs::QueryTrajectoryState::Request &req,
00083                          pr2_controllers_msgs::QueryTrajectoryState::Response &resp);
00084   ros::ServiceServer serve_query_state_;
00085 
00086   boost::scoped_ptr<
00087     realtime_tools::RealtimePublisher<
00088       pr2_controllers_msgs::JointTrajectoryControllerState> > controller_state_publisher_;
00089 
00090 
00091   // ------ Mechanisms for passing the trajectory into realtime
00092 
00093   // coef[0] + coef[1]*t + ... + coef[5]*t^5
00094   struct Spline
00095   {
00096     std::vector<double> coef;
00097 
00098     Spline() : coef(6, 0.0) {}
00099   };
00100 
00101   struct Segment
00102   {
00103     double start_time;
00104     double duration;
00105     std::vector<Spline> splines;
00106   };
00107   typedef std::vector<Segment> SpecifiedTrajectory;
00108 
00109   realtime_tools::RealtimeBox<
00110     boost::shared_ptr<const SpecifiedTrajectory> > current_trajectory_box_;
00111 
00112   // Holds the trajectory that we are currently following.  The mutex
00113   // guarding current_trajectory_ is locked from within realtime, so
00114   // it may only be locked for a bounded duration.
00115   //boost::shared_ptr<const SpecifiedTrajectory> current_trajectory_;
00116   //boost::recursive_mutex current_trajectory_lock_RT_;
00117 
00118   std::vector<double> q, qd, qdd;  // Preallocated in init
00119 
00120   // Samples, but handling time bounds.  When the time is past the end
00121   // of the spline duration, the position is the last valid position,
00122   // and the derivatives are all 0.
00123   static void sampleSplineWithTimeBounds(const std::vector<double>& coefficients, double duration, double time,
00124                                          double& position, double& velocity, double& acceleration);
00125 };
00126 
00127 }
00128 
00129 #endif


robot_mechanism_controllers
Author(s): John Hsu, Melonee Wise, Stuart Glaser
autogenerated on Thu Aug 27 2015 14:22:45