Go to the documentation of this file.00001 
00002 
00003 
00004 
00005 
00006 
00007 
00008 
00009 
00010 
00011 
00012 
00013 
00014 
00015 
00016 
00017 
00018 
00019 
00020 
00021 
00022 
00023 
00024 
00025 
00026 
00027 
00028 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 #include <effort_controllers/joint_velocity_controller.h>
00037 #include <pluginlib/class_list_macros.h>
00038 
00039 
00040 namespace effort_controllers {
00041 
00042 JointVelocityController::JointVelocityController()
00043 : command_(0), loop_count_(0)
00044 {}
00045 
00046 JointVelocityController::~JointVelocityController()
00047 {
00048   sub_command_.shutdown();
00049 }
00050 
00051 bool JointVelocityController::init(hardware_interface::EffortJointInterface *robot, 
00052   const std::string &joint_name, const control_toolbox::Pid &pid)
00053 {
00054   pid_controller_ = pid;
00055 
00056   
00057   joint_ = robot->getHandle(joint_name);
00058 
00059   return true;
00060 }
00061 
00062 bool JointVelocityController::init(hardware_interface::EffortJointInterface *robot, ros::NodeHandle &n)
00063 {
00064   
00065   std::string joint_name;
00066   if (!n.getParam("joint", joint_name)) {
00067     ROS_ERROR("No joint given (namespace: %s)", n.getNamespace().c_str());
00068     return false;
00069   }
00070 
00071   
00072   joint_ = robot->getHandle(joint_name);
00073 
00074   
00075   if (!pid_controller_.init(ros::NodeHandle(n, "pid")))
00076     return false;
00077 
00078   
00079   controller_state_publisher_.reset(
00080     new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>
00081     (n, "state", 1));
00082 
00083   
00084   sub_command_ = n.subscribe<std_msgs::Float64>("command", 1, &JointVelocityController::setCommandCB, this);
00085 
00086   return true;
00087 }
00088 
00089 
00090 void JointVelocityController::setGains(const double &p, const double &i, const double &d, const double &i_max, const double &i_min)
00091 {
00092   pid_controller_.setGains(p,i,d,i_max,i_min);
00093 
00094 }
00095 
00096 void JointVelocityController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00097 {
00098   pid_controller_.getGains(p,i,d,i_max,i_min);
00099 }
00100 
00101 void JointVelocityController::printDebug()
00102 {
00103   pid_controller_.printValues();
00104 }
00105 
00106 std::string JointVelocityController::getJointName()
00107 {
00108   return joint_.getName();
00109 }
00110 
00111 
00112 void JointVelocityController::setCommand(double cmd)
00113 {
00114   command_ = cmd;
00115 }
00116 
00117 
00118 void JointVelocityController::getCommand(double& cmd)
00119 {
00120   cmd = command_;
00121 }
00122 
00123 void JointVelocityController::starting(const ros::Time& time)
00124 {
00125   command_ = 0.0;
00126   pid_controller_.reset();
00127 }
00128 
00129 void JointVelocityController::update(const ros::Time& time, const ros::Duration& period)
00130 {
00131   double error = command_ - joint_.getVelocity();
00132 
00133   
00134   
00135   
00136   double commanded_effort = pid_controller_.computeCommand(error, period);
00137 
00138   joint_.setCommand(commanded_effort);
00139 
00140   if(loop_count_ % 10 == 0)
00141   {
00142     if(controller_state_publisher_ && controller_state_publisher_->trylock())
00143     {
00144       controller_state_publisher_->msg_.header.stamp = time;
00145       controller_state_publisher_->msg_.set_point = command_;
00146       controller_state_publisher_->msg_.process_value = joint_.getVelocity();
00147       controller_state_publisher_->msg_.error = error;
00148       controller_state_publisher_->msg_.time_step = period.toSec();
00149       controller_state_publisher_->msg_.command = commanded_effort;
00150 
00151       double dummy;
00152       getGains(controller_state_publisher_->msg_.p,
00153                controller_state_publisher_->msg_.i,
00154                controller_state_publisher_->msg_.d,
00155                controller_state_publisher_->msg_.i_clamp,
00156                dummy);
00157       controller_state_publisher_->unlockAndPublish();
00158     }
00159   }
00160   loop_count_++;
00161 }
00162 
00163 void JointVelocityController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
00164 {
00165   command_ = msg->data;
00166 }
00167 
00168 } 
00169 
00170 PLUGINLIB_EXPORT_CLASS( effort_controllers::JointVelocityController, controller_interface::ControllerBase)