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  *  Copyright (c) 2013, University of Colorado, Boulder
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of the Willow Garage nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *********************************************************************/
00036 
00037 /*
00038  Author: Dave Coleman
00039  Contributors: Jonathan Bohren, Wim Meeussen, Vijay Pradeep
00040  Desc: Velocity-based position controller using basic PID loop
00041 */
00042 
00043 #ifndef VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00044 #define VELOCITY_CONTROLLERS__JOINT_POSITION_CONTROLLER_H
00045 
00069 #include <ros/node_handle.h>
00070 #include <urdf/model.h>
00071 #include <control_toolbox/pid.h>
00072 #include <boost/scoped_ptr.hpp>
00073 #include <boost/thread/condition.hpp>
00074 #include <realtime_tools/realtime_publisher.h>
00075 #include <hardware_interface/joint_command_interface.h>
00076 #include <controller_interface/controller.h>
00077 #include <control_msgs/JointControllerState.h>
00078 #include <std_msgs/Float64.h>
00079 #include <control_msgs/JointControllerState.h>
00080 #include <realtime_tools/realtime_buffer.h>
00081 
00082 namespace velocity_controllers
00083 {
00084 
00085 class JointPositionController: public controller_interface::Controller<hardware_interface::VelocityJointInterface>
00086 {
00087 public:
00088 
00092   struct Commands
00093   {
00094     double position_; // Last commanded position
00095     double velocity_; // Last commanded velocity
00096     bool has_velocity_; // false if no velocity command has been specified
00097   };
00098 
00099   JointPositionController();
00100   ~JointPositionController();
00101 
00115   bool init(hardware_interface::VelocityJointInterface *robot, ros::NodeHandle &n);
00116 
00122   void setCommand(double pos_target);
00123 
00131   void setCommand(double pos_target, double vel_target);
00132 
00138   void starting(const ros::Time& time);
00139   
00143   void update(const ros::Time& time, const ros::Duration& period);
00144 
00148   void getGains(double &p, double &i, double &d, double &i_max, double &i_min);
00149 
00153   void printDebug();
00154 
00158   void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min);
00159 
00163   std::string getJointName();
00164 
00169   double getPosition();
00170 
00171   hardware_interface::JointHandle joint_;
00172   boost::shared_ptr<const urdf::Joint> joint_urdf_;
00173   realtime_tools::RealtimeBuffer<Commands> command_;
00174   Commands command_struct_; // pre-allocated memory that is re-used to set the realtime buffer
00175 
00176 private:
00177   int loop_count_;
00178   control_toolbox::Pid pid_controller_;       
00180   boost::scoped_ptr<
00181     realtime_tools::RealtimePublisher<
00182       control_msgs::JointControllerState> > controller_state_publisher_ ;
00183 
00184   ros::Subscriber sub_command_;
00185 
00189   void setCommandCB(const std_msgs::Float64ConstPtr& msg);
00190 
00196   void enforceJointLimits(double &command);
00197 
00198 };
00199 
00200 } // namespace
00201 
00202 #endif


velocity_controllers
Author(s): Vijay Pradeep
autogenerated on Sat Aug 13 2016 04:20:59