Go to the documentation of this file.00001
00036 #ifndef PID_H
00037 #define PID_H
00038
00039 #include "ros/ros.h"
00040 #include <dynamic_reconfigure/server.h>
00041 #include <iostream>
00042 #include <pid/PidConfig.h>
00043 #include <ros/time.h>
00044 #include <std_msgs/Bool.h>
00045 #include <std_msgs/Float64.h>
00046 #include <std_msgs/Float64MultiArray.h>
00047 #include <stdio.h>
00048 #include <string>
00049
00050 namespace pid_ns
00051 {
00052 class PidObject
00053 {
00054 public:
00055 PidObject();
00056
00057
00058 double control_effort_ = 0;
00059
00060 private:
00061 void doCalcs();
00062 void getParams(double in, double& value, double& scale);
00063 void pidEnableCallback(const std_msgs::Bool& pid_enable_msg);
00064 void plantStateCallback(const std_msgs::Float64& state_msg);
00065 void printParameters();
00066 void reconfigureCallback(pid::PidConfig& config, uint32_t level);
00067 void setpointCallback(const std_msgs::Float64& setpoint_msg);
00068 bool validateParameters();
00069
00070
00071 double plant_state_;
00072 bool pid_enabled_ = true;
00073 bool new_state_or_setpt_ = false;
00074 double setpoint_ = 0;
00075
00076 ros::Time prev_time_;
00077 ros::Duration delta_t_;
00078 bool first_reconfig_ = true;
00079
00080 double error_integral_ = 0;
00081 double proportional_ = 0;
00082 double integral_ = 0;
00083 double derivative_ = 0;
00084
00085
00086 double Kp_ = 0, Ki_ = 0, Kd_ = 0;
00087
00088
00089 bool angle_error_ = false;
00090 double angle_wrap_ = 2.0 * 3.14159;
00091
00092
00093
00094 double cutoff_frequency_ = -1;
00095
00096
00097
00098
00099 double c_ = 1.;
00100
00101
00102 double tan_filt_ = 1.;
00103
00104
00105 double upper_limit_ = 1000, lower_limit_ = -1000;
00106
00107
00108 double windup_limit_ = 1000;
00109
00110
00111 std::vector<double> error_, filtered_error_, error_deriv_, filtered_error_deriv_;
00112
00113
00114 ros::Publisher control_effort_pub_;
00115 ros::Publisher pid_debug_pub_;
00116
00117 std::string topic_from_controller_, topic_from_plant_, setpoint_topic_, pid_enable_topic_;
00118 std::string pid_debug_pub_name_;
00119 std_msgs::Float64 control_msg_, state_msg_;
00120
00121
00122 double min_loop_frequency_ = 1, max_loop_frequency_ = 1000;
00123 int measurements_received_ = 0;
00124 };
00125 }
00126
00127 #endif