6 PidObject::PidObject() : error_(3, 0), filtered_error_(3, 0), error_deriv_(3, 0), filtered_error_deriv_(3, 0)
13 ROS_INFO(
"controller spinning, waiting for time to become non-zero");
19 node_priv.
param<
double>(
"Kp",
Kp_, 1.0);
20 node_priv.
param<
double>(
"Ki",
Ki_, 0.0);
21 node_priv.
param<
double>(
"Kd",
Kd_, 0.0);
41 std::cout <<
"Error: invalid parameter\n";
51 if (!plant_sub_ || !setpoint_sub_ || !pid_enabled_sub_)
59 dynamic_reconfigure::Server<pid::PidConfig> config_server;
60 dynamic_reconfigure::Server<pid::PidConfig>::CallbackType
f;
62 config_server.setCallback(f);
65 while(
ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(setpoint_topic_,
ros::Duration(10.)))
68 while(
ros::ok() && !ros::topic::waitForMessage<std_msgs::Float64>(topic_from_plant_,
ros::Duration(10.)))
105 while (
ros::ok() && ((fabs(value) > 1.0 || fabs(value) < 0.1) && (digits < 2 && digits > -1)))
107 if (fabs(value) > 1.0)
123 scale = pow(10.0, digits);
130 ROS_ERROR(
"The lower saturation limit cannot be greater than the upper " 131 "saturation limit.");
140 std::cout << std::endl <<
"PID PARAMETERS" << std::endl <<
"-----------------------------------------" << std::endl;
141 std::cout <<
"Kp: " <<
Kp_ <<
", Ki: " <<
Ki_ <<
", Kd: " <<
Kd_ << std::endl;
143 std::cout <<
"LPF cutoff frequency: 1/4 of sampling rate" << std::endl;
149 std::cout <<
"Name of setpoint topic: " <<
setpoint_topic_ << std::endl;
150 std::cout <<
"Integral-windup limit: " <<
windup_limit_ << std::endl;
152 std::cout <<
"-----------------------------------------" << std::endl;
179 if (!((
Kp_ <= 0. &&
Ki_ <= 0. &&
Kd_ <= 0.) ||
181 ROS_WARN(
"All three gains (Kp, Ki, Kd) should have the same sign for " 213 ROS_ERROR(
"delta_t is 0, skipping this loop. Possible overloaded cpu " 221 ROS_INFO(
"prev_time is 0, doing nothing");
269 (1 / (1 +
c_ *
c_ + 1.414 *
c_)) *
292 std_msgs::Float64MultiArray pidDebugMsg;
293 pidDebugMsg.data = pid_debug_vect;
297 error_integral_ = 0.0;
std::string topic_from_controller_
std::vector< double > filtered_error_deriv_
ros::Publisher control_effort_pub_
std::string pid_debug_pub_name_
void publish(const boost::shared_ptr< M > &message) const
double max_loop_frequency_
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
std::vector< double > error_deriv_
ROSCPP_DECL const std::string & getName()
double min_loop_frequency_
std::string topic_from_plant_
std::string pid_enable_topic_
std::string setpoint_topic_
bool validateParameters()
void reconfigureCallback(pid::PidConfig &config, uint32_t level)
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
ros::Publisher pid_debug_pub_
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
#define ROS_WARN_STREAM(args)
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_
ROSCPP_DECL void shutdown()
#define ROS_ERROR_STREAM(args)
ROSCPP_DECL void spinOnce()
void getParams(double in, double &value, double &scale)
void plantStateCallback(const std_msgs::Float64 &state_msg)
std::vector< double > error_