pid.cpp
Go to the documentation of this file.
00001 
00002 #include <pid/pid.h>
00003 
00004 using namespace pid_ns;
00005 
00006 PidObject::PidObject() : error_(3, 0), filtered_error_(3, 0), error_deriv_(3, 0), filtered_error_deriv_(3, 0)
00007 {
00008   ros::NodeHandle node;
00009   ros::NodeHandle node_priv("~");
00010 
00011   while (ros::ok() && ros::Time(0) == ros::Time::now())
00012   {
00013     ROS_INFO("controller spinning, waiting for time to become non-zero");
00014     sleep(1);
00015   }
00016 
00017   // Get params if specified in launch file or as params on command-line, set
00018   // defaults
00019   node_priv.param<double>("Kp", Kp_, 1.0);
00020   node_priv.param<double>("Ki", Ki_, 0.0);
00021   node_priv.param<double>("Kd", Kd_, 0.0);
00022   node_priv.param<double>("upper_limit", upper_limit_, 1000.0);
00023   node_priv.param<double>("lower_limit", lower_limit_, -1000.0);
00024   node_priv.param<double>("windup_limit", windup_limit_, 1000.0);
00025   node_priv.param<double>("cutoff_frequency", cutoff_frequency_, -1.0);
00026   node_priv.param<std::string>("topic_from_controller", topic_from_controller_, "control_effort");
00027   node_priv.param<std::string>("topic_from_plant", topic_from_plant_, "state");
00028   node_priv.param<std::string>("setpoint_topic", setpoint_topic_, "setpoint");
00029   node_priv.param<std::string>("pid_enable_topic", pid_enable_topic_, "pid_enable");
00030   node_priv.param<double>("max_loop_frequency", max_loop_frequency_, 1.0);
00031   node_priv.param<double>("min_loop_frequency", min_loop_frequency_, 1000.0);
00032   node_priv.param<std::string>("pid_debug_topic", pid_debug_pub_name_, "pid_debug");
00033 
00034   // Two parameters to allow for error calculation with discontinous value
00035   node_priv.param<bool>("angle_error", angle_error_, false);
00036   node_priv.param<double>("angle_wrap", angle_wrap_, 2.0 * 3.14159);
00037 
00038   // Update params if specified as command-line options, & print settings
00039   printParameters();
00040   if (not validateParameters())
00041     std::cout << "Error: invalid parameter\n";
00042 
00043   // instantiate publishers & subscribers
00044   control_effort_pub_ = node.advertise<std_msgs::Float64>(topic_from_controller_, 1);
00045   pid_debug_pub_ = node.advertise<std_msgs::Float64MultiArray>(pid_debug_pub_name_, 1);
00046 
00047   ros::Subscriber plant_sub_ = node.subscribe(topic_from_plant_, 1, &PidObject::plantStateCallback, this);
00048   ros::Subscriber setpoint_sub_ = node.subscribe(setpoint_topic_, 1, &PidObject::setpointCallback, this);
00049   ros::Subscriber pid_enabled_sub_ = node.subscribe(pid_enable_topic_, 1, &PidObject::pidEnableCallback, this);
00050 
00051   if (!plant_sub_ || !setpoint_sub_ || !pid_enabled_sub_)
00052   {
00053     ROS_ERROR_STREAM("Initialization of a subscriber failed. Exiting.");
00054     ros::shutdown();
00055     exit(EXIT_FAILURE);
00056   }
00057 
00058   // dynamic reconfiguration
00059   dynamic_reconfigure::Server<pid::PidConfig> config_server;
00060   dynamic_reconfigure::Server<pid::PidConfig>::CallbackType f;
00061   f = boost::bind(&PidObject::reconfigureCallback, this, _1, _2);
00062   config_server.setCallback(f);
00063 
00064   // Wait for first messages
00065   while( ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(setpoint_topic_, ros::Duration(10.)))
00066      ROS_WARN_STREAM("Waiting for first setpoint message.");
00067 
00068   while( ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(topic_from_plant_, ros::Duration(10.)))
00069      ROS_WARN_STREAM("Waiting for first state message from the plant.");
00070 
00071   // Respond to inputs until shut down
00072   while (ros::ok())
00073   {
00074     doCalcs();
00075     ros::spinOnce();
00076 
00077     // Add a small sleep to avoid 100% CPU usage
00078     ros::Duration(0.001).sleep();
00079   }
00080 };
00081 
00082 void PidObject::setpointCallback(const std_msgs::Float64& setpoint_msg)
00083 {
00084   setpoint_ = setpoint_msg.data;
00085 
00086   new_state_or_setpt_ = true;
00087 }
00088 
00089 void PidObject::plantStateCallback(const std_msgs::Float64& state_msg)
00090 {
00091   plant_state_ = state_msg.data;
00092 
00093   new_state_or_setpt_ = true;
00094 }
00095 
00096 void PidObject::pidEnableCallback(const std_msgs::Bool& pid_enable_msg)
00097 {
00098   pid_enabled_ = pid_enable_msg.data;
00099 }
00100 
00101 void PidObject::getParams(double in, double& value, double& scale)
00102 {
00103   int digits = 0;
00104   value = in;
00105   while (ros::ok() && ((fabs(value) > 1.0 || fabs(value) < 0.1) && (digits < 2 && digits > -1)))
00106   {
00107     if (fabs(value) > 1.0)
00108     {
00109       value /= 10.0;
00110       digits++;
00111     }
00112     else
00113     {
00114       value *= 10.0;
00115       digits--;
00116     }
00117   }
00118   if (value > 1.0)
00119     value = 1.0;
00120   if (value < -1.0)
00121     value = -1.0;
00122 
00123   scale = pow(10.0, digits);
00124 }
00125 
00126 bool PidObject::validateParameters()
00127 {
00128   if (lower_limit_ > upper_limit_)
00129   {
00130     ROS_ERROR("The lower saturation limit cannot be greater than the upper "
00131               "saturation limit.");
00132     return (false);
00133   }
00134 
00135   return true;
00136 }
00137 
00138 void PidObject::printParameters()
00139 {
00140   std::cout << std::endl << "PID PARAMETERS" << std::endl << "-----------------------------------------" << std::endl;
00141   std::cout << "Kp: " << Kp_ << ",  Ki: " << Ki_ << ",  Kd: " << Kd_ << std::endl;
00142   if (cutoff_frequency_ == -1)  // If the cutoff frequency was not specified by the user
00143     std::cout << "LPF cutoff frequency: 1/4 of sampling rate" << std::endl;
00144   else
00145     std::cout << "LPF cutoff frequency: " << cutoff_frequency_ << std::endl;
00146   std::cout << "pid node name: " << ros::this_node::getName() << std::endl;
00147   std::cout << "Name of topic from controller: " << topic_from_controller_ << std::endl;
00148   std::cout << "Name of topic from the plant: " << topic_from_plant_ << std::endl;
00149   std::cout << "Name of setpoint topic: " << setpoint_topic_ << std::endl;
00150   std::cout << "Integral-windup limit: " << windup_limit_ << std::endl;
00151   std::cout << "Saturation limits: " << upper_limit_ << "/" << lower_limit_ << std::endl;
00152   std::cout << "-----------------------------------------" << std::endl;
00153 
00154   return;
00155 }
00156 
00157 void PidObject::reconfigureCallback(pid::PidConfig& config, uint32_t level)
00158 {
00159   if (first_reconfig_)
00160   {
00161     getParams(Kp_, config.Kp, config.Kp_scale);
00162     getParams(Ki_, config.Ki, config.Ki_scale);
00163     getParams(Kd_, config.Kd, config.Kd_scale);
00164     first_reconfig_ = false;
00165     return;  // Ignore the first call to reconfigure which happens at startup
00166   }
00167 
00168   Kp_ = config.Kp * config.Kp_scale;
00169   Ki_ = config.Ki * config.Ki_scale;
00170   Kd_ = config.Kd * config.Kd_scale;
00171   ROS_INFO("Pid reconfigure request: Kp: %f, Ki: %f, Kd: %f", Kp_, Ki_, Kd_);
00172 }
00173 
00174 void PidObject::doCalcs()
00175 {
00176   // Do fresh calcs if knowledge of the system has changed.
00177   if (new_state_or_setpt_)
00178   {
00179     if (!((Kp_ <= 0. && Ki_ <= 0. && Kd_ <= 0.) ||
00180           (Kp_ >= 0. && Ki_ >= 0. && Kd_ >= 0.)))  // All 3 gains should have the same sign
00181       ROS_WARN("All three gains (Kp, Ki, Kd) should have the same sign for "
00182                "stability.");
00183 
00184     error_.at(2) = error_.at(1);
00185     error_.at(1) = error_.at(0);
00186     error_.at(0) = setpoint_ - plant_state_;  // Current error goes to slot 0
00187 
00188     // If the angle_error param is true, then address discontinuity in error
00189     // calc.
00190     // For example, this maintains an angular error between -180:180.
00191     if (angle_error_)
00192     {
00193       while (error_.at(0) < -1.0 * angle_wrap_ / 2.0)
00194         error_.at(0) += angle_wrap_;
00195       while (error_.at(0) > angle_wrap_ / 2.0)
00196         error_.at(0) -= angle_wrap_;
00197 
00198       // The proportional error will flip sign, but the integral error
00199       // won't and the derivative error will be poorly defined. So,
00200       // reset them.
00201       error_.at(2) = 0.;
00202       error_.at(1) = 0.;
00203       error_integral_ = 0.;
00204     }
00205 
00206     // calculate delta_t
00207     if (!prev_time_.isZero())  // Not first time through the program
00208     {
00209       delta_t_ = ros::Time::now() - prev_time_;
00210       prev_time_ = ros::Time::now();
00211       if (0 == delta_t_.toSec())
00212       {
00213         ROS_ERROR("delta_t is 0, skipping this loop. Possible overloaded cpu "
00214                   "at time: %f",
00215                   ros::Time::now().toSec());
00216         return;
00217       }
00218     }
00219     else
00220     {
00221       ROS_INFO("prev_time is 0, doing nothing");
00222       prev_time_ = ros::Time::now();
00223       return;
00224     }
00225 
00226     // integrate the error
00227     error_integral_ += error_.at(0) * delta_t_.toSec();
00228 
00229     // Apply windup limit to limit the size of the integral term
00230     if (error_integral_ > fabsf(windup_limit_))
00231       error_integral_ = fabsf(windup_limit_);
00232 
00233     if (error_integral_ < -fabsf(windup_limit_))
00234       error_integral_ = -fabsf(windup_limit_);
00235 
00236     // My filter reference was Julius O. Smith III, Intro. to Digital Filters
00237     // With Audio Applications.
00238     // See https://ccrma.stanford.edu/~jos/filters/Example_Second_Order_Butterworth_Lowpass.html
00239     if (cutoff_frequency_ != -1)
00240     {
00241       // Check if tan(_) is really small, could cause c = NaN
00242       tan_filt_ = tan((cutoff_frequency_ * 6.2832) * delta_t_.toSec() / 2);
00243 
00244       // Avoid tan(0) ==> NaN
00245       if ((tan_filt_ <= 0.) && (tan_filt_ > -0.01))
00246         tan_filt_ = -0.01;
00247       if ((tan_filt_ >= 0.) && (tan_filt_ < 0.01))
00248         tan_filt_ = 0.01;
00249 
00250       c_ = 1 / tan_filt_;
00251     }
00252 
00253     filtered_error_.at(2) = filtered_error_.at(1);
00254     filtered_error_.at(1) = filtered_error_.at(0);
00255     filtered_error_.at(0) = (1 / (1 + c_ * c_ + 1.414 * c_)) * (error_.at(2) + 2 * error_.at(1) + error_.at(0) -
00256                                                                 (c_ * c_ - 1.414 * c_ + 1) * filtered_error_.at(2) -
00257                                                                 (-2 * c_ * c_ + 2) * filtered_error_.at(1));
00258 
00259     // Take derivative of error
00260     // First the raw, unfiltered data:
00261     error_deriv_.at(2) = error_deriv_.at(1);
00262     error_deriv_.at(1) = error_deriv_.at(0);
00263     error_deriv_.at(0) = (error_.at(0) - error_.at(1)) / delta_t_.toSec();
00264 
00265     filtered_error_deriv_.at(2) = filtered_error_deriv_.at(1);
00266     filtered_error_deriv_.at(1) = filtered_error_deriv_.at(0);
00267 
00268     filtered_error_deriv_.at(0) =
00269         (1 / (1 + c_ * c_ + 1.414 * c_)) *
00270         (error_deriv_.at(2) + 2 * error_deriv_.at(1) + error_deriv_.at(0) -
00271          (c_ * c_ - 1.414 * c_ + 1) * filtered_error_deriv_.at(2) - (-2 * c_ * c_ + 2) * filtered_error_deriv_.at(1));
00272 
00273     // calculate the control effort
00274     proportional_ = Kp_ * filtered_error_.at(0);
00275     integral_ = Ki_ * error_integral_;
00276     derivative_ = Kd_ * filtered_error_deriv_.at(0);
00277     control_effort_ = proportional_ + integral_ + derivative_;
00278 
00279     // Apply saturation limits
00280     if (control_effort_ > upper_limit_)
00281       control_effort_ = upper_limit_;
00282     else if (control_effort_ < lower_limit_)
00283       control_effort_ = lower_limit_;
00284 
00285     // Publish the stabilizing control effort if the controller is enabled
00286     if (pid_enabled_)
00287     {
00288       control_msg_.data = control_effort_;
00289       control_effort_pub_.publish(control_msg_);
00290       // Publish topic with
00291       std::vector<double> pid_debug_vect { plant_state_, control_effort_, proportional_, integral_, derivative_};
00292       std_msgs::Float64MultiArray pidDebugMsg;
00293       pidDebugMsg.data = pid_debug_vect;
00294       pid_debug_pub_.publish(pidDebugMsg);
00295     }
00296     else
00297       error_integral_ = 0.0;
00298   }
00299 
00300   new_state_or_setpt_ = false;
00301 }


pid
Author(s): Andy Zelenak , Paul Bouchier
autogenerated on Mon Apr 15 2019 02:40:47