controller.h
Go to the documentation of this file.
1 /***************************************************************************/
36 #ifndef CONTROLLER_H
37 #define CONTROLLER_H
38 
39 namespace pid_ns
40 {
41 class PidObject
42 {
43 public:
44  PidObject();
45 
46 private:
47  void doCalcs();
48  void getParams(double in, double& value, double& scale);
49  void pidEnableCallback(const std_msgs::Bool& pid_enable_msg);
50  void plantStateCallback(const std_msgs::Float64& state_msg);
51  void printParameters();
52  void reconfigureCallback(pid::PidConfig& config, uint32_t level);
53  void setpointCallback(const std_msgs::Float64& setpoint_msg);
54  bool validateParameters();
55 
56  // Primary PID controller input & output variables
57  double plant_state_; // current output of plant
58  double control_effort_ = 0; // output of pid controller
59  double setpoint_ = 0; // desired output of plant
60  bool pid_enabled_ = true; // PID is enabled to run
61  bool new_state_or_setpt_ = false; // Indicate that fresh calculations need to be run
62 
65  bool first_reconfig_ = true;
66 
67  double error_integral_ = 0;
68  double proportional_ = 0; // proportional term of output
69  double integral_ = 0; // integral term of output
70  double derivative_ = 0; // derivative term of output
71 
72  // PID gains
73  double Kp_ = 0, Ki_ = 0, Kd_ = 0;
74 
75  // Parameters for error calc. with disconinuous input
76  bool angle_error_ = false;
77  double angle_wrap_ = 2.0 * 3.14159;
78 
79  // Cutoff frequency for the derivative calculation in Hz.
80  // Negative -> Has not been set by the user yet, so use a default.
81  double cutoff_frequency_ = -1;
82 
83  // Used in filter calculations. Default 1.0 corresponds to a cutoff frequency
84  // at
85  // 1/4 of the sample rate.
86  double c_ = 1.;
87 
88  // Used to check for tan(0)==>NaN in the filter calculation
89  double tan_filt_ = 1.;
90 
91  // Upper and lower saturation limits
92  double upper_limit_ = 1000, lower_limit_ = -1000;
93 
94  // Anti-windup term. Limits the absolute value of the integral term.
95  double windup_limit_ = 1000;
96 
97  // Initialize filter data with zeros
99 
100  // Topic and node names and message objects
103 
104  std_msgs::Float64 control_msg_, state_msg_;
105 
106  // Diagnostic objects
109 };
110 } // end pid namespace
111 
112 #endif
pid_ns::PidObject::Kd_
double Kd_
Definition: controller.h:73
pid_ns::PidObject::doCalcs
void doCalcs()
Definition: pid.cpp:177
pid_ns::PidObject::getParams
void getParams(double in, double &value, double &scale)
Definition: pid.cpp:104
ros::Publisher
pid_ns::PidObject::Kp_
double Kp_
Definition: controller.h:73
pid_ns
Definition: controller.h:39
pid_ns::PidObject::first_reconfig_
bool first_reconfig_
Definition: controller.h:65
pid_ns::PidObject::Ki_
double Ki_
Definition: controller.h:73
pid_ns::PidObject::state_msg_
std_msgs::Float64 state_msg_
Definition: controller.h:104
pid_ns::PidObject::tan_filt_
double tan_filt_
Definition: controller.h:89
pid_ns::PidObject::derivative_
double derivative_
Definition: controller.h:70
pid_ns::PidObject::reconfigureCallback
void reconfigureCallback(pid::PidConfig &config, uint32_t level)
Definition: pid.cpp:160
pid_ns::PidObject::topic_from_plant_
std::string topic_from_plant_
Definition: controller.h:102
pid_ns::PidObject::c_
double c_
Definition: controller.h:86
pid_ns::PidObject::setpoint_
double setpoint_
Definition: controller.h:59
pid_ns::PidObject::pidEnableCallback
void pidEnableCallback(const std_msgs::Bool &pid_enable_msg)
Definition: pid.cpp:99
pid_ns::PidObject::PidObject
PidObject()
Definition: pid.cpp:6
pid_ns::PidObject::prev_time_
ros::Time prev_time_
Definition: controller.h:63
pid_ns::PidObject::plantStateCallback
void plantStateCallback(const std_msgs::Float64 &state_msg)
Definition: pid.cpp:92
pid_ns::PidObject::cutoff_frequency_
double cutoff_frequency_
Definition: controller.h:81
pid_ns::PidObject::min_loop_frequency_
double min_loop_frequency_
Definition: controller.h:107
pid_ns::PidObject::angle_error_
bool angle_error_
Definition: controller.h:76
pid_ns::PidObject::pid_enabled_
bool pid_enabled_
Definition: controller.h:60
pid_ns::PidObject::integral_
double integral_
Definition: controller.h:69
pid_ns::PidObject::control_msg_
std_msgs::Float64 control_msg_
Definition: controller.h:104
pid_ns::PidObject::plant_state_
double plant_state_
Definition: controller.h:57
pid_ns::PidObject::windup_limit_
double windup_limit_
Definition: controller.h:95
pid_ns::PidObject::filtered_error_
std::vector< double > filtered_error_
Definition: controller.h:98
pid_ns::PidObject::topic_from_controller_
std::string topic_from_controller_
Definition: controller.h:102
pid_ns::PidObject::printParameters
void printParameters()
Definition: pid.cpp:141
pid_ns::PidObject::new_state_or_setpt_
bool new_state_or_setpt_
Definition: controller.h:61
pid_ns::PidObject::pid_enable_topic_
std::string pid_enable_topic_
Definition: controller.h:102
ros::Time
pid_ns::PidObject::error_deriv_
std::vector< double > error_deriv_
Definition: controller.h:98
pid_ns::PidObject::filtered_error_deriv_
std::vector< double > filtered_error_deriv_
Definition: controller.h:98
pid_ns::PidObject::error_integral_
double error_integral_
Definition: controller.h:67
pid_ns::PidObject::control_effort_pub_
ros::Publisher control_effort_pub_
Definition: controller.h:101
pid_ns::PidObject::error_
std::vector< double > error_
Definition: controller.h:98
pid_ns::PidObject::angle_wrap_
double angle_wrap_
Definition: controller.h:77
pid_ns::PidObject::measurements_received_
int measurements_received_
Definition: controller.h:108
pid_ns::PidObject::delta_t_
ros::Duration delta_t_
Definition: controller.h:64
pid::PidConfig
Definition: PidConfig.h:22
pid_ns::PidObject::setpoint_topic_
std::string setpoint_topic_
Definition: controller.h:102
pid_ns::PidObject
Definition: controller.h:41
pid_ns::PidObject::max_loop_frequency_
double max_loop_frequency_
Definition: controller.h:107
pid_ns::PidObject::lower_limit_
double lower_limit_
Definition: controller.h:92
pid_ns::PidObject::control_effort_
double control_effort_
Definition: controller.h:58
ros::Duration
pid_ns::PidObject::upper_limit_
double upper_limit_
Definition: controller.h:92
pid_ns::PidObject::proportional_
double proportional_
Definition: controller.h:68
pid_ns::PidObject::setpointCallback
void setpointCallback(const std_msgs::Float64 &setpoint_msg)
Definition: pid.cpp:85
pid_ns::PidObject::validateParameters
bool validateParameters()
Definition: pid.cpp:129


pid
Author(s): Andy Zelenak , Paul Bouchier
autogenerated on Wed Mar 2 2022 00:41:32