srh_joint_position_controller.cpp
Go to the documentation of this file.
00001 
00027 #include "sr_mechanism_controllers/srh_joint_position_controller.hpp"
00028 #include "angles/angles.h"
00029 #include "pluginlib/class_list_macros.h"
00030 #include <sstream>
00031 #include <math.h>
00032 #include "sr_utilities/sr_math_utils.hpp"
00033 
00034 #include <std_msgs/Float64.h>
00035 
00036 PLUGINLIB_EXPORT_CLASS(controller::SrhJointPositionController, controller_interface::ControllerBase)
00037 
00038 using namespace std;
00039 
00040 namespace controller
00041 {
00042 
00043 SrhJointPositionController::SrhJointPositionController()
00044   : position_deadband(0.015)
00045 {
00046 }
00047 
00048 bool SrhJointPositionController::init(ros_ethercat_model::RobotState *robot, ros::NodeHandle &n)
00049 {
00050   ROS_ASSERT(robot);
00051   robot_ = robot;
00052   node_ = n;
00053 
00054   if (!node_.getParam("joint", joint_name_))
00055   {
00056     ROS_ERROR("No joint given (namespace: %s)", node_.getNamespace().c_str());
00057     return false;
00058   }
00059 
00060   pid_controller_position_.reset(new control_toolbox::Pid());
00061   if (!pid_controller_position_->init(ros::NodeHandle(node_, "pid")))
00062     return false;
00063 
00064   controller_state_publisher_.reset(new realtime_tools::RealtimePublisher<control_msgs::JointControllerState>
00065                                     (node_, "state", 1));
00066 
00067   ROS_DEBUG(" --------- ");
00068   ROS_DEBUG_STREAM("Init: " << joint_name_);
00069 
00070   // joint 0s e.g. FFJ0
00071   has_j2 = is_joint_0();
00072   if (has_j2)
00073   {
00074     get_joints_states_1_2();
00075     if (!joint_state_)
00076     {
00077       ROS_ERROR("SrhJointPositionController could not find the first joint relevant to \"%s\"\n", joint_name_.c_str());
00078       return false;
00079     }
00080     if (!joint_state_2)
00081     {
00082       ROS_ERROR("SrhJointPositionController could not find the second joint relevant to \"%s\"\n", joint_name_.c_str());
00083       return false;
00084     }
00085     if (!joint_state_2->calibrated_)
00086     {
00087       ROS_ERROR("Joint %s not calibrated for SrhJointPositionController", joint_name_.c_str());
00088       return false;
00089     }
00090     else
00091       joint_state_->calibrated_ = true;
00092   }
00093   else
00094   {
00095     joint_state_ = robot_->getJointState(joint_name_);
00096     if (!joint_state_)
00097     {
00098       ROS_ERROR("SrhJointPositionController could not find joint named \"%s\"\n", joint_name_.c_str());
00099       return false;
00100     }
00101     if (!joint_state_->calibrated_)
00102     {
00103       ROS_ERROR("Joint %s not calibrated for SrhJointPositionController", joint_name_.c_str());
00104       return false;
00105     }
00106   }
00107 
00108   //get the min and max value for the current joint:
00109   get_min_max(robot_->robot_model_, joint_name_);
00110 
00111   friction_compensator.reset(new sr_friction_compensation::SrFrictionCompensator(joint_name_));
00112 
00113   serve_set_gains_ = node_.advertiseService("set_gains", &SrhJointPositionController::setGains, this);
00114   serve_reset_gains_ = node_.advertiseService("reset_gains", &SrhJointPositionController::resetGains, this);
00115 
00116   after_init();
00117   return true;
00118 }
00119 
00120 void SrhJointPositionController::starting(const ros::Time& time)
00121 {
00122   resetJointState();
00123   pid_controller_position_->reset();
00124   read_parameters();
00125 
00126   if (has_j2)
00127     ROS_WARN_STREAM("Reseting PID for joints " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
00128   else
00129     ROS_WARN_STREAM("Reseting PID for joint  " << joint_state_->joint_->name);
00130 }
00131 
00132 bool SrhJointPositionController::setGains(sr_robot_msgs::SetPidGains::Request &req,
00133                                           sr_robot_msgs::SetPidGains::Response &resp)
00134 {
00135   ROS_INFO_STREAM("Setting new PID parameters. P:" << req.p << " / I:" << req.i <<
00136                   " / D:" << req.d << " / IClamp:" << req.i_clamp << ", max force: " <<
00137                   req.max_force << ", friction deadband: " << req.friction_deadband <<
00138                   " pos deadband: " << req.deadband);
00139 
00140   pid_controller_position_->setGains(req.p, req.i, req.d, req.i_clamp, -req.i_clamp);
00141   max_force_demand = req.max_force;
00142   friction_deadband = req.friction_deadband;
00143   position_deadband = req.deadband;
00144 
00145   //Setting the new parameters in the parameter server
00146   node_.setParam("pid/p", req.p);
00147   node_.setParam("pid/i", req.i);
00148   node_.setParam("pid/d", req.d);
00149   node_.setParam("pid/i_clamp", req.i_clamp);
00150   node_.setParam("pid/max_force", max_force_demand);
00151   node_.setParam("pid/position_deadband", position_deadband);
00152   node_.setParam("pid/friction_deadband", friction_deadband);
00153 
00154   return true;
00155 }
00156 
00157 bool SrhJointPositionController::resetGains(std_srvs::Empty::Request& req, std_srvs::Empty::Response& resp)
00158 {
00159   resetJointState();
00160 
00161   if (!pid_controller_position_->init(ros::NodeHandle(node_, "pid")))
00162     return false;
00163 
00164   read_parameters();
00165 
00166   if (has_j2)
00167     ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name << " and " << joint_state_2->joint_->name);
00168   else
00169     ROS_WARN_STREAM("Reseting controller gains: " << joint_state_->joint_->name);
00170 
00171   return true;
00172 }
00173 
00174 void SrhJointPositionController::getGains(double &p, double &i, double &d, double &i_max, double &i_min)
00175 {
00176   pid_controller_position_->getGains(p, i, d, i_max, i_min);
00177 }
00178 
00179 void SrhJointPositionController::update(const ros::Time& time, const ros::Duration& period)
00180 {
00181   if (!has_j2 && !joint_state_->calibrated_)
00182     return;
00183 
00184   ROS_ASSERT(robot_);
00185   ROS_ASSERT(joint_state_->joint_);
00186 
00187   if (!initialized_)
00188   {
00189     resetJointState();
00190     initialized_ = true;
00191   }
00192   if (has_j2)
00193     command_ = joint_state_->commanded_position_ + joint_state_2->commanded_position_;
00194   else
00195     command_ = joint_state_->commanded_position_;
00196   command_ = clamp_command(command_);
00197 
00198   //Compute position demand from position error:
00199   double error_position = 0.0;
00200   double commanded_effort = 0.0;
00201 
00202   if (has_j2)
00203     error_position = (joint_state_->position_ + joint_state_2->position_) - command_;
00204   else
00205     error_position = joint_state_->position_ - command_;
00206 
00207   bool in_deadband = hysteresis_deadband.is_in_deadband(command_, error_position, position_deadband);
00208 
00209   //don't compute the error if we're in the deadband.
00210   if (in_deadband)
00211     error_position = 0.0;
00212 
00213   commanded_effort = pid_controller_position_->computeCommand(-error_position, period);
00214 
00215   //clamp the result to max force
00216   commanded_effort = min(commanded_effort, (max_force_demand * max_force_factor_));
00217   commanded_effort = max(commanded_effort, -(max_force_demand * max_force_factor_));
00218 
00219   if (!in_deadband)
00220   {
00221     if (has_j2)
00222       commanded_effort += friction_compensator->friction_compensation(joint_state_->position_ + joint_state_2->position_,
00223                                                                       joint_state_->velocity_ + joint_state_2->velocity_,
00224                                                                       int(commanded_effort),
00225                                                                       friction_deadband);
00226     else
00227       commanded_effort += friction_compensator->friction_compensation(joint_state_->position_,
00228                                                                       joint_state_->velocity_,
00229                                                                       int(commanded_effort),
00230                                                                       friction_deadband);
00231   }
00232 
00233   joint_state_->commanded_effort_ = commanded_effort;
00234 
00235   if (loop_count_ % 10 == 0)
00236   {
00237     if (controller_state_publisher_ && controller_state_publisher_->trylock())
00238     {
00239       controller_state_publisher_->msg_.header.stamp = time;
00240       controller_state_publisher_->msg_.set_point = command_;
00241       if (has_j2)
00242       {
00243         controller_state_publisher_->msg_.process_value = joint_state_->position_ + joint_state_2->position_;
00244         controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_ + joint_state_2->velocity_;
00245       }
00246       else
00247       {
00248         controller_state_publisher_->msg_.process_value = joint_state_->position_;
00249         controller_state_publisher_->msg_.process_value_dot = joint_state_->velocity_;
00250       }
00251 
00252       controller_state_publisher_->msg_.error = error_position;
00253       controller_state_publisher_->msg_.time_step = period.toSec();
00254       controller_state_publisher_->msg_.command = commanded_effort;
00255 
00256       double dummy;
00257       getGains(controller_state_publisher_->msg_.p,
00258                controller_state_publisher_->msg_.i,
00259                controller_state_publisher_->msg_.d,
00260                controller_state_publisher_->msg_.i_clamp,
00261                dummy);
00262       controller_state_publisher_->unlockAndPublish();
00263     }
00264   }
00265   loop_count_++;
00266 }
00267 
00268 void SrhJointPositionController::read_parameters()
00269 {
00270   node_.param<double>("pid/max_force", max_force_demand, 1023.0);
00271   node_.param<double>("pid/position_deadband", position_deadband, 0.015);
00272   node_.param<int>("pid/friction_deadband", friction_deadband, 5);
00273 }
00274 
00275 void SrhJointPositionController::setCommandCB(const std_msgs::Float64ConstPtr& msg)
00276 {
00277   joint_state_->commanded_position_ = msg->data;
00278   if (has_j2)
00279     joint_state_2->commanded_position_ = 0.0;
00280 }
00281 
00282 void SrhJointPositionController::resetJointState()
00283 {
00284     if (has_j2)
00285     {
00286       joint_state_->commanded_position_ = joint_state_->position_;
00287       joint_state_2->commanded_position_ = joint_state_2->position_;
00288       command_ = joint_state_->position_ + joint_state_2->position_;
00289     }
00290     else
00291     {
00292       joint_state_->commanded_position_ = joint_state_->position_;
00293       command_ = joint_state_->position_;
00294     }
00295 }
00296 }
00297 
00298 /* For the emacs weenies in the crowd.
00299 Local Variables:
00300    c-basic-offset: 2
00301 End:
00302  */
00303 
00304 


sr_mechanism_controllers
Author(s): Ugo Cupcic
autogenerated on Fri Aug 21 2015 12:26:14