pid.cpp
Go to the documentation of this file.
1 
2 #include <pid/pid.h>
3 
4 using namespace pid_ns;
5 
6 PidObject::PidObject() : error_(3, 0), filtered_error_(3, 0), error_deriv_(3, 0), filtered_error_deriv_(3, 0)
7 {
8  ros::NodeHandle node;
9  ros::NodeHandle node_priv("~");
10 
11  while (ros::ok() && ros::Time(0) == ros::Time::now())
12  {
13  ROS_INFO("controller spinning, waiting for time to become non-zero");
14  sleep(1);
15  }
16 
17  // Get params if specified in launch file or as params on command-line, set
18  // defaults
19  node_priv.param<double>("Kp", Kp_, 1.0);
20  node_priv.param<double>("Ki", Ki_, 0.0);
21  node_priv.param<double>("Kd", Kd_, 0.0);
22  node_priv.param<double>("upper_limit", upper_limit_, 1000.0);
23  node_priv.param<double>("lower_limit", lower_limit_, -1000.0);
24  node_priv.param<double>("windup_limit", windup_limit_, 1000.0);
25  node_priv.param<double>("cutoff_frequency", cutoff_frequency_, -1.0);
26  node_priv.param<std::string>("topic_from_controller", topic_from_controller_, "control_effort");
27  node_priv.param<std::string>("topic_from_plant", topic_from_plant_, "state");
28  node_priv.param<std::string>("setpoint_topic", setpoint_topic_, "setpoint");
29  node_priv.param<std::string>("pid_enable_topic", pid_enable_topic_, "pid_enable");
30  node_priv.param<double>("max_loop_frequency", max_loop_frequency_, 1.0);
31  node_priv.param<double>("min_loop_frequency", min_loop_frequency_, 1000.0);
32  node_priv.param<std::string>("pid_debug_topic", pid_debug_pub_name_, "pid_debug");
33 
34  // Two parameters to allow for error calculation with discontinous value
35  node_priv.param<bool>("angle_error", angle_error_, false);
36  node_priv.param<double>("angle_wrap", angle_wrap_, 2.0 * 3.14159);
37 
38  // Update params if specified as command-line options, & print settings
40  if (not validateParameters())
41  std::cout << "Error: invalid parameter\n";
42 
43  // instantiate publishers & subscribers
44  control_effort_pub_ = node.advertise<std_msgs::Float64>(topic_from_controller_, 1);
45  pid_debug_pub_ = node.advertise<std_msgs::Float64MultiArray>(pid_debug_pub_name_, 1);
46 
47  ros::Subscriber plant_sub_ = node.subscribe(topic_from_plant_, 1, &PidObject::plantStateCallback, this);
48  ros::Subscriber setpoint_sub_ = node.subscribe(setpoint_topic_, 1, &PidObject::setpointCallback, this);
49  ros::Subscriber pid_enabled_sub_ = node.subscribe(pid_enable_topic_, 1, &PidObject::pidEnableCallback, this);
50 
51  if (!plant_sub_ || !setpoint_sub_ || !pid_enabled_sub_)
52  {
53  ROS_ERROR_STREAM("Initialization of a subscriber failed. Exiting.");
54  ros::shutdown();
55  exit(EXIT_FAILURE);
56  }
57 
58  // dynamic reconfiguration
59  dynamic_reconfigure::Server<pid::PidConfig> config_server;
60  dynamic_reconfigure::Server<pid::PidConfig>::CallbackType f;
61  f = boost::bind(&PidObject::reconfigureCallback, this, _1, _2);
62  config_server.setCallback(f);
63 
64  // Wait for first messages
65  while( ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(setpoint_topic_, ros::Duration(10.)))
66  ROS_WARN_STREAM("Waiting for first setpoint message.");
67 
68  while( ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(topic_from_plant_, ros::Duration(10.)))
69  ROS_WARN_STREAM("Waiting for first state message from the plant.");
70 
71  // Respond to inputs until shut down
72  while (ros::ok())
73  {
74  doCalcs();
75  ros::spinOnce();
76 
77  // Add a small sleep to avoid 100% CPU usage
78  ros::Duration(0.001).sleep();
79  }
80 };
81 
82 void PidObject::setpointCallback(const std_msgs::Float64& setpoint_msg)
83 {
84  setpoint_ = setpoint_msg.data;
85 
86  new_state_or_setpt_ = true;
87 }
88 
89 void PidObject::plantStateCallback(const std_msgs::Float64& state_msg)
90 {
91  plant_state_ = state_msg.data;
92 
93  new_state_or_setpt_ = true;
94 }
95 
96 void PidObject::pidEnableCallback(const std_msgs::Bool& pid_enable_msg)
97 {
98  pid_enabled_ = pid_enable_msg.data;
99 }
100 
101 void PidObject::getParams(double in, double& value, double& scale)
102 {
103  int digits = 0;
104  value = in;
105  while (ros::ok() && ((fabs(value) > 1.0 || fabs(value) < 0.1) && (digits < 2 && digits > -1)))
106  {
107  if (fabs(value) > 1.0)
108  {
109  value /= 10.0;
110  digits++;
111  }
112  else
113  {
114  value *= 10.0;
115  digits--;
116  }
117  }
118  if (value > 1.0)
119  value = 1.0;
120  if (value < -1.0)
121  value = -1.0;
122 
123  scale = pow(10.0, digits);
124 }
125 
127 {
129  {
130  ROS_ERROR("The lower saturation limit cannot be greater than the upper "
131  "saturation limit.");
132  return (false);
133  }
134 
135  return true;
136 }
137 
139 {
140  std::cout << std::endl << "PID PARAMETERS" << std::endl << "-----------------------------------------" << std::endl;
141  std::cout << "Kp: " << Kp_ << ", Ki: " << Ki_ << ", Kd: " << Kd_ << std::endl;
142  if (cutoff_frequency_ == -1) // If the cutoff frequency was not specified by the user
143  std::cout << "LPF cutoff frequency: 1/4 of sampling rate" << std::endl;
144  else
145  std::cout << "LPF cutoff frequency: " << cutoff_frequency_ << std::endl;
146  std::cout << "pid node name: " << ros::this_node::getName() << std::endl;
147  std::cout << "Name of topic from controller: " << topic_from_controller_ << std::endl;
148  std::cout << "Name of topic from the plant: " << topic_from_plant_ << std::endl;
149  std::cout << "Name of setpoint topic: " << setpoint_topic_ << std::endl;
150  std::cout << "Integral-windup limit: " << windup_limit_ << std::endl;
151  std::cout << "Saturation limits: " << upper_limit_ << "/" << lower_limit_ << std::endl;
152  std::cout << "-----------------------------------------" << std::endl;
153 
154  return;
155 }
156 
157 void PidObject::reconfigureCallback(pid::PidConfig& config, uint32_t level)
158 {
159  if (first_reconfig_)
160  {
161  getParams(Kp_, config.Kp, config.Kp_scale);
162  getParams(Ki_, config.Ki, config.Ki_scale);
163  getParams(Kd_, config.Kd, config.Kd_scale);
164  first_reconfig_ = false;
165  return; // Ignore the first call to reconfigure which happens at startup
166  }
167 
168  Kp_ = config.Kp * config.Kp_scale;
169  Ki_ = config.Ki * config.Ki_scale;
170  Kd_ = config.Kd * config.Kd_scale;
171  ROS_INFO("Pid reconfigure request: Kp: %f, Ki: %f, Kd: %f", Kp_, Ki_, Kd_);
172 }
173 
175 {
176  // Do fresh calcs if knowledge of the system has changed.
178  {
179  if (!((Kp_ <= 0. && Ki_ <= 0. && Kd_ <= 0.) ||
180  (Kp_ >= 0. && Ki_ >= 0. && Kd_ >= 0.))) // All 3 gains should have the same sign
181  ROS_WARN("All three gains (Kp, Ki, Kd) should have the same sign for "
182  "stability.");
183 
184  error_.at(2) = error_.at(1);
185  error_.at(1) = error_.at(0);
186  error_.at(0) = setpoint_ - plant_state_; // Current error goes to slot 0
187 
188  // If the angle_error param is true, then address discontinuity in error
189  // calc.
190  // For example, this maintains an angular error between -180:180.
191  if (angle_error_)
192  {
193  while (error_.at(0) < -1.0 * angle_wrap_ / 2.0)
194  error_.at(0) += angle_wrap_;
195  while (error_.at(0) > angle_wrap_ / 2.0)
196  error_.at(0) -= angle_wrap_;
197 
198  // The proportional error will flip sign, but the integral error
199  // won't and the derivative error will be poorly defined. So,
200  // reset them.
201  error_.at(2) = 0.;
202  error_.at(1) = 0.;
203  error_integral_ = 0.;
204  }
205 
206  // calculate delta_t
207  if (!prev_time_.isZero()) // Not first time through the program
208  {
211  if (0 == delta_t_.toSec())
212  {
213  ROS_ERROR("delta_t is 0, skipping this loop. Possible overloaded cpu "
214  "at time: %f",
215  ros::Time::now().toSec());
216  return;
217  }
218  }
219  else
220  {
221  ROS_INFO("prev_time is 0, doing nothing");
223  return;
224  }
225 
226  // integrate the error
227  error_integral_ += error_.at(0) * delta_t_.toSec();
228 
229  // Apply windup limit to limit the size of the integral term
230  if (error_integral_ > fabsf(windup_limit_))
232 
233  if (error_integral_ < -fabsf(windup_limit_))
234  error_integral_ = -fabsf(windup_limit_);
235 
236  // My filter reference was Julius O. Smith III, Intro. to Digital Filters
237  // With Audio Applications.
238  // See https://ccrma.stanford.edu/~jos/filters/Example_Second_Order_Butterworth_Lowpass.html
239  if (cutoff_frequency_ != -1)
240  {
241  // Check if tan(_) is really small, could cause c = NaN
242  tan_filt_ = tan((cutoff_frequency_ * 6.2832) * delta_t_.toSec() / 2);
243 
244  // Avoid tan(0) ==> NaN
245  if ((tan_filt_ <= 0.) && (tan_filt_ > -0.01))
246  tan_filt_ = -0.01;
247  if ((tan_filt_ >= 0.) && (tan_filt_ < 0.01))
248  tan_filt_ = 0.01;
249 
250  c_ = 1 / tan_filt_;
251  }
252 
253  filtered_error_.at(2) = filtered_error_.at(1);
254  filtered_error_.at(1) = filtered_error_.at(0);
255  filtered_error_.at(0) = (1 / (1 + c_ * c_ + 1.414 * c_)) * (error_.at(2) + 2 * error_.at(1) + error_.at(0) -
256  (c_ * c_ - 1.414 * c_ + 1) * filtered_error_.at(2) -
257  (-2 * c_ * c_ + 2) * filtered_error_.at(1));
258 
259  // Take derivative of error
260  // First the raw, unfiltered data:
261  error_deriv_.at(2) = error_deriv_.at(1);
262  error_deriv_.at(1) = error_deriv_.at(0);
263  error_deriv_.at(0) = (error_.at(0) - error_.at(1)) / delta_t_.toSec();
264 
267 
268  filtered_error_deriv_.at(0) =
269  (1 / (1 + c_ * c_ + 1.414 * c_)) *
270  (error_deriv_.at(2) + 2 * error_deriv_.at(1) + error_deriv_.at(0) -
271  (c_ * c_ - 1.414 * c_ + 1) * filtered_error_deriv_.at(2) - (-2 * c_ * c_ + 2) * filtered_error_deriv_.at(1));
272 
273  // calculate the control effort
278 
279  // Apply saturation limits
282  else if (control_effort_ < lower_limit_)
284 
285  // Publish the stabilizing control effort if the controller is enabled
286  if (pid_enabled_)
287  {
290  // Publish topic with
291  std::vector<double> pid_debug_vect { plant_state_, control_effort_, proportional_, integral_, derivative_};
292  std_msgs::Float64MultiArray pidDebugMsg;
293  pidDebugMsg.data = pid_debug_vect;
294  pid_debug_pub_.publish(pidDebugMsg);
295  }
296  else
297  error_integral_ = 0.0;
298  }
299 
300  new_state_or_setpt_ = false;
301 }
ros::Duration delta_t_
Definition: controller.h:64
std::string topic_from_controller_
Definition: controller.h:102
std::vector< double > filtered_error_deriv_
Definition: controller.h:98
ros::Publisher control_effort_pub_
Definition: controller.h:101
std::string pid_debug_pub_name_
Definition: pid.h:118
void publish(const boost::shared_ptr< M > &message) const
f
double max_loop_frequency_
Definition: controller.h:107
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool sleep() const
std::vector< double > error_deriv_
Definition: controller.h:98
ROSCPP_DECL const std::string & getName()
double plant_state_
Definition: controller.h:57
double windup_limit_
Definition: controller.h:95
#define ROS_WARN(...)
double min_loop_frequency_
Definition: controller.h:107
std::string topic_from_plant_
Definition: controller.h:102
std::string pid_enable_topic_
Definition: controller.h:102
double Ki_scale
Definition: PidConfig.h:268
std::string setpoint_topic_
Definition: controller.h:102
bool new_state_or_setpt_
Definition: controller.h:61
double upper_limit_
Definition: controller.h:92
double Kd_scale
Definition: PidConfig.h:274
double error_integral_
Definition: controller.h:67
bool validateParameters()
Definition: pid.cpp:126
double derivative_
Definition: controller.h:70
#define ROS_INFO(...)
ros::Time prev_time_
Definition: controller.h:63
void reconfigureCallback(pid::PidConfig &config, uint32_t level)
Definition: pid.cpp:157
bool param(const std::string &param_name, T &param_val, const T &default_val) const
double cutoff_frequency_
Definition: controller.h:81
ROSCPP_DECL bool ok()
double angle_wrap_
Definition: controller.h:77
ros::Publisher pid_debug_pub_
Definition: pid.h:115
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
double lower_limit_
Definition: controller.h:92
#define ROS_WARN_STREAM(args)
double control_effort_
Definition: controller.h:58
void doCalcs()
Definition: pid.cpp:174
std::vector< double > filtered_error_
Definition: controller.h:98
void pidEnableCallback(const std_msgs::Bool &pid_enable_msg)
Definition: pid.cpp:96
void setpointCallback(const std_msgs::Float64 &setpoint_msg)
Definition: pid.cpp:82
double Kp_scale
Definition: PidConfig.h:262
std_msgs::Float64 control_msg_
Definition: controller.h:104
static Time now()
void printParameters()
Definition: pid.cpp:138
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
void getParams(double in, double &value, double &scale)
Definition: pid.cpp:101
#define ROS_ERROR(...)
double proportional_
Definition: controller.h:68
void plantStateCallback(const std_msgs::Float64 &state_msg)
Definition: pid.cpp:89
std::vector< double > error_
Definition: controller.h:98


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