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
00057 double plant_state_;
00058 double control_effort_ = 0;
00059 double setpoint_ = 0;
00060 bool pid_enabled_ = true;
00061 bool new_state_or_setpt_ = false;
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;
00069 double integral_ = 0;
00070 double derivative_ = 0;
00071
00072
00073 double Kp_ = 0, Ki_ = 0, Kd_ = 0;
00074
00075
00076 bool angle_error_ = false;
00077 double angle_wrap_ = 2.0 * 3.14159;
00078
00079
00080
00081 double cutoff_frequency_ = -1;
00082
00083
00084
00085
00086 double c_ = 1.;
00087
00088
00089 double tan_filt_ = 1.;
00090
00091
00092 double upper_limit_ = 1000, lower_limit_ = -1000;
00093
00094
00095 double windup_limit_ = 1000;
00096
00097
00098 std::vector<double> error_, filtered_error_, error_deriv_, filtered_error_deriv_;
00099
00100
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
00107 double min_loop_frequency_ = 1, max_loop_frequency_ = 1000;
00108 int measurements_received_ = 0;
00109 };
00110 }
00111
00112 #endif