$search
00001 /********************************************************************* 00002 * Software License Agreement (BSD License) 00003 * 00004 * Copyright (c) 2008, Willow Garage, Inc. 00005 * All rights reserved. 00006 * 00007 * Redistribution and use in source and binary forms, with or without 00008 * modification, are permitted provided that the following conditions 00009 * are met: 00010 * 00011 * * Redistributions of source code must retain the above copyright 00012 * notice, this list of conditions and the following disclaimer. 00013 * * Redistributions in binary form must reproduce the above 00014 * copyright notice, this list of conditions and the following 00015 * disclaimer in the documentation and/or other materials provided 00016 * with the distribution. 00017 * * Neither the name of the Willow Garage nor the names of its 00018 * contributors may be used to endorse or promote products derived 00019 * from this software without specific prior written permission. 00020 * 00021 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS 00022 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT 00023 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS 00024 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE 00025 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, 00026 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, 00027 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 00028 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 00029 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT 00030 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN 00031 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE 00032 * POSSIBILITY OF SUCH DAMAGE. 00033 *********************************************************************/ 00034 00035 #ifndef JOINT_POSITION_CONTROLLER_H 00036 #define JOINT_POSITION_CONTROLLER_H 00037 00061 #include <ros/node_handle.h> 00062 00063 #include <pr2_controller_interface/controller.h> 00064 #include <control_toolbox/pid.h> 00065 #include "control_toolbox/pid_gains_setter.h" 00066 #include <boost/scoped_ptr.hpp> 00067 #include <boost/thread/condition.hpp> 00068 #include <realtime_tools/realtime_publisher.h> 00069 #include <std_msgs/Float64.h> 00070 #include <pr2_controllers_msgs/JointControllerState.h> 00071 00072 namespace controller 00073 { 00074 00075 class JointPositionController : public pr2_controller_interface::Controller 00076 { 00077 public: 00078 00079 JointPositionController(); 00080 ~JointPositionController(); 00081 00082 bool init(pr2_mechanism_model::RobotState *robot, const std::string &joint_name,const control_toolbox::Pid &pid); 00083 bool init(pr2_mechanism_model::RobotState *robot, ros::NodeHandle &n); 00084 00090 void setCommand(double cmd); 00091 00095 void getCommand(double & cmd); 00096 00097 virtual void starting() { 00098 command_ = joint_state_->position_; 00099 pid_controller_.reset(); 00100 } 00101 00105 virtual void update(); 00106 00107 void getGains(double &p, double &i, double &d, double &i_max, double &i_min); 00108 void setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min); 00109 00110 std::string getJointName(); 00111 pr2_mechanism_model::JointState *joint_state_; 00112 ros::Duration dt_; 00113 double command_; 00115 private: 00116 int loop_count_; 00117 bool initialized_; 00118 pr2_mechanism_model::RobotState *robot_; 00119 control_toolbox::Pid pid_controller_; 00120 ros::Time last_time_; 00123 ros::NodeHandle node_; 00124 00125 boost::scoped_ptr< 00126 realtime_tools::RealtimePublisher< 00127 pr2_controllers_msgs::JointControllerState> > controller_state_publisher_ ; 00128 00129 ros::Subscriber sub_command_; 00130 void setCommandCB(const std_msgs::Float64ConstPtr& msg); 00131 }; 00132 00133 } // namespace 00134 00135 #endif