joint_position_controller.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2008, Willow Garage, Inc.
00005  *  Copyright (c) 2012, hiDOF, 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 the Willow Garage 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 #ifndef EFFORT_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00037 #define EFFORT_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00038 
00062 #include <ros/node_handle.h>
00063 #include <urdf/model.h>
00064 #include <control_toolbox/pid.h>
00065 #include <boost/scoped_ptr.hpp>
00066 #include <boost/thread/condition.hpp>
00067 #include <realtime_tools/realtime_publisher.h>
00068 #include <hardware_interface/joint_command_interface.h>
00069 #include <controller_interface/controller.h>
00070 #include <control_msgs/JointControllerState.h>
00071 #include <std_msgs/Float64.h>
00072 #include <control_msgs/JointControllerState.h>
00073 #include <realtime_tools/realtime_buffer.h>
00074 
00075 namespace effort_controllers
00076 {
00077 
00078 class JointPositionController: public controller_interface::Controller<hardware_interface::EffortJointInterface>
00079 {
00080 public:
00081 
00085   struct Commands
00086   {
00087     double position_; // Last commanded position
00088     double velocity_; // Last commanded velocity
00089     bool has_velocity_; // false if no velocity command has been specified
00090   };
00091 
00092   JointPositionController();
00093   ~JointPositionController();
00094 
00108   bool init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n);
00109 
00115   void setCommand(double pos_target);
00116 
00124   void setCommand(double pos_target, double vel_target);
00125 
00131   void starting(const ros::Time& time);
00132   
00136   void update(const ros::Time& time, const ros::Duration& period);
00137 
00141   void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00142 
00146   void printDebug();
00147 
00151   void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
00152 
00156   std::string getJointName();
00157 
00162   double getPosition();
00163 
00164   hardware_interface::JointHandle joint_;
00165   boost::shared_ptr<const urdf::Joint> joint_urdf_;
00166   realtime_tools::RealtimeBuffer<Commands> command_;
00167   Commands command_struct_; // pre-allocated memory that is re-used to set the realtime buffer
00168 
00169 private:
00170   int loop_count_;
00171   control_toolbox::Pid pid_controller_;       
00173   boost::scoped_ptr<
00174     realtime_tools::RealtimePublisher<
00175       control_msgs::JointControllerState> > controller_state_publisher_ ;
00176 
00177   ros::Subscriber sub_command_;
00178 
00182   void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00183 
00189   void enforceJointLimits(double &command);
00190 
00191 };
00192 
00193 } // namespace
00194 
00195 #endif


effort_controllers
Author(s): Vijay Pradeep
autogenerated on Fri Aug 28 2015 12:37:06