pid.h
Go to the documentation of this file.
1 /***************************************************************************/
36 #ifndef PID_H
37 #define PID_H
38 
39 #include "ros/ros.h"
40 #include <dynamic_reconfigure/server.h>
41 #include <iostream>
42 #include <pid/PidConfig.h>
43 #include <ros/time.h>
44 #include <std_msgs/Bool.h>
45 #include <std_msgs/Float64.h>
46 #include <std_msgs/Float64MultiArray.h>
47 #include <stdio.h>
48 #include <string>
49 
50 namespace pid_ns
51 {
52 class PidObject
53 {
54 public:
55  PidObject();
56 
57  // Primary output variable
58  double control_effort_ = 0; // output of pid controller
59 
60 private:
61  void doCalcs();
62  void getParams(double in, double& value, double& scale);
63  void pidEnableCallback(const std_msgs::Bool& pid_enable_msg);
64  void plantStateCallback(const std_msgs::Float64& state_msg);
65  void printParameters();
66  void reconfigureCallback(pid::PidConfig& config, uint32_t level);
67  void setpointCallback(const std_msgs::Float64& setpoint_msg);
68  bool validateParameters();
69 
70  // Primary PID controller input variables
71  double plant_state_; // current output of plant
72  bool pid_enabled_ = true; // PID is enabled to run
73  bool new_state_or_setpt_ = false; // Indicate that fresh calculations need to be run
74  double setpoint_ = 0; // desired output of plant
75 
79  bool first_reconfig_ = true;
80 
81  double error_integral_ = 0;
82  double proportional_ = 0; // proportional term of output
83  double integral_ = 0; // integral term of output
84  double derivative_ = 0; // derivative term of output
85 
86  // PID gains
87  double Kp_ = 0, Ki_ = 0, Kd_ = 0;
88 
89  // Parameters for error calc. with disconinuous input
90  bool angle_error_ = false;
91  double angle_wrap_ = 2.0 * 3.14159;
92 
93  // Cutoff frequency for the derivative calculation in Hz.
94  // Negative -> Has not been set by the user yet, so use a default.
95  double cutoff_frequency_ = -1;
96 
97  // Setpoint timeout parameter to determine how long to keep publishing
98  // control_effort messages after last setpoint message
99  // -1 indicates publish indefinately, and positive number sets the timeout
100  double setpoint_timeout_ = -1;
101 
102  // Used in filter calculations. Default 1.0 corresponds to a cutoff frequency
103  // at
104  // 1/4 of the sample rate.
105  double c_ = 1.;
106 
107  // Used to check for tan(0)==>NaN in the filter calculation
108  double tan_filt_ = 1.;
109 
110  // Upper and lower saturation limits
111  double upper_limit_ = 1000, lower_limit_ = -1000;
112 
113  // Anti-windup term. Limits the absolute value of the integral term.
114  double windup_limit_ = 1000;
115 
116  // Initialize filter data with zeros
118 
119  // Topic and node names and message objects
122 
124  std::string pid_debug_pub_name_;
125  std_msgs::Float64 control_msg_, state_msg_;
126 
127  // Diagnostic objects
128  double min_loop_frequency_ = 1, max_loop_frequency_ = 1000;
129  int measurements_received_ = 0;
130 };
131 } // end pid namespace
132 
133 #endif
pid_ns::PidObject::last_setpoint_msg_time_
ros::Time last_setpoint_msg_time_
Definition: pid.h:77
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
ros.h
pid_ns::PidObject::topic_from_plant_
std::string topic_from_plant_
Definition: controller.h:102
time.h
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::pid_debug_pub_name_
std::string pid_debug_pub_name_
Definition: pid.h:124
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::pid_debug_pub_
ros::Publisher pid_debug_pub_
Definition: pid.h:121
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::setpoint_timeout_
double setpoint_timeout_
Definition: pid.h:100
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
PidConfig.h
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::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