controller.h
Go to the documentation of this file.
00001 /***************************************************************************/ 
00036 #ifndef CONTROLLER_H
00037 #define CONTROLLER_H
00038 
00039 namespace pid_ns
00040 {
00041 class PidObject
00042 {
00043 public:
00044   PidObject();
00045 
00046 private:
00047   void doCalcs();
00048   void getParams(double in, double& value, double& scale);
00049   void pidEnableCallback(const std_msgs::Bool& pid_enable_msg);
00050   void plantStateCallback(const std_msgs::Float64& state_msg);
00051   void printParameters();
00052   void reconfigureCallback(pid::PidConfig& config, uint32_t level);
00053   void setpointCallback(const std_msgs::Float64& setpoint_msg);
00054   bool validateParameters();
00055 
00056   // Primary PID controller input & output variables
00057   double plant_state_;               // current output of plant
00058   double control_effort_ = 0;        // output of pid controller
00059   double setpoint_ = 0;              // desired output of plant
00060   bool pid_enabled_ = true;          // PID is enabled to run
00061   bool new_state_or_setpt_ = false;  // Indicate that fresh calculations need to be run
00062 
00063   ros::Time prev_time_;
00064   ros::Duration delta_t_;
00065   bool first_reconfig_ = true;
00066 
00067   double error_integral_ = 0;
00068   double proportional_ = 0;  // proportional term of output
00069   double integral_ = 0;      // integral term of output
00070   double derivative_ = 0;    // derivative term of output
00071 
00072   // PID gains
00073   double Kp_ = 0, Ki_ = 0, Kd_ = 0;
00074 
00075   // Parameters for error calc. with disconinuous input
00076   bool angle_error_ = false;
00077   double angle_wrap_ = 2.0 * 3.14159;
00078 
00079   // Cutoff frequency for the derivative calculation in Hz.
00080   // Negative -> Has not been set by the user yet, so use a default.
00081   double cutoff_frequency_ = -1;
00082 
00083   // Used in filter calculations. Default 1.0 corresponds to a cutoff frequency
00084   // at
00085   // 1/4 of the sample rate.
00086   double c_ = 1.;
00087 
00088   // Used to check for tan(0)==>NaN in the filter calculation
00089   double tan_filt_ = 1.;
00090 
00091   // Upper and lower saturation limits
00092   double upper_limit_ = 1000, lower_limit_ = -1000;
00093 
00094   // Anti-windup term. Limits the absolute value of the integral term.
00095   double windup_limit_ = 1000;
00096 
00097   // Initialize filter data with zeros
00098   std::vector<double> error_, filtered_error_, error_deriv_, filtered_error_deriv_;
00099 
00100   // Topic and node names and message objects
00101   ros::Publisher control_effort_pub_;
00102   std::string topic_from_controller_, topic_from_plant_, setpoint_topic_, pid_enable_topic_;
00103 
00104   std_msgs::Float64 control_msg_, state_msg_;
00105 
00106   // Diagnostic objects
00107   double min_loop_frequency_ = 1, max_loop_frequency_ = 1000;
00108   int measurements_received_ = 0;
00109 };
00110 }  // end pid namespace
00111 
00112 #endif


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