40 #include <dynamic_reconfigure/server.h> 44 #include <std_msgs/Bool.h> 45 #include <std_msgs/Float64.h> 46 #include <std_msgs/Float64MultiArray.h> 62 void getParams(
double in,
double& value,
double& scale);
std::string topic_from_controller_
std::vector< double > filtered_error_deriv_
ros::Publisher control_effort_pub_
std::string pid_debug_pub_name_
double max_loop_frequency_
std::vector< double > error_deriv_
double min_loop_frequency_
std::string topic_from_plant_
std::string pid_enable_topic_
std::string setpoint_topic_
bool validateParameters()
std_msgs::Float64 state_msg_
void reconfigureCallback(pid::PidConfig &config, uint32_t level)
ros::Publisher pid_debug_pub_
int measurements_received_
std::vector< double > filtered_error_
void pidEnableCallback(const std_msgs::Bool &pid_enable_msg)
void setpointCallback(const std_msgs::Float64 &setpoint_msg)
std_msgs::Float64 control_msg_
void getParams(double in, double &value, double &scale)
void plantStateCallback(const std_msgs::Float64 &state_msg)
std::vector< double > error_