Go to the documentation of this file.
    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);
 
   44     std::cout << 
"Error: invalid parameter\n";
 
   54   if (!plant_sub_ || !setpoint_sub_ || !pid_enabled_sub_)
 
   62   dynamic_reconfigure::Server<pid::PidConfig> config_server;
 
   63   dynamic_reconfigure::Server<pid::PidConfig>::CallbackType 
f;
 
   65   config_server.setCallback(
f);
 
  108   while (
ros::ok() && ((fabs(value) > 1.0 || fabs(value) < 0.1) && (digits < 2 && digits > -1)))
 
  110     if (fabs(value) > 1.0)
 
  126   scale = pow(10.0, digits);
 
  133     ROS_ERROR(
"The lower saturation limit cannot be greater than the upper " 
  134               "saturation limit.");
 
  143   std::cout << std::endl << 
"PID PARAMETERS" << std::endl << 
"-----------------------------------------" << std::endl;
 
  144   std::cout << 
"Kp: " << 
Kp_ << 
",  Ki: " << 
Ki_ << 
",  Kd: " << 
Kd_ << std::endl;
 
  146     std::cout << 
"LPF cutoff frequency: 1/4 of sampling rate" << std::endl;
 
  152   std::cout << 
"Name of setpoint topic: " << 
setpoint_topic_ << std::endl;
 
  153   std::cout << 
"Integral-windup limit: " << 
windup_limit_ << std::endl;
 
  155   std::cout << 
"-----------------------------------------" << std::endl;
 
  182     if (!((
Kp_ <= 0. && 
Ki_ <= 0. && 
Kd_ <= 0.) ||
 
  184       ROS_WARN(
"All three gains (Kp, Ki, Kd) should have the same sign for " 
  229         ROS_ERROR(
"delta_t is 0, skipping this loop. Possible overloaded cpu " 
  237       ROS_INFO(
"prev_time is 0, doing nothing");
 
  285         (1 / (1 + 
c_ * 
c_ + 1.414 * 
c_)) *
 
  309       std_msgs::Float64MultiArray pidDebugMsg;
 
  310       pidDebugMsg.data = pid_debug_vect;
 
  315       ROS_WARN_ONCE(
"Setpoint message timed out, will stop publising control_effort_messages");
 
  
ros::Time last_setpoint_msg_time_
void getParams(double in, double &value, double &scale)
#define ROS_ERROR_STREAM(args)
void reconfigureCallback(pid::PidConfig &config, uint32_t level)
std::string topic_from_plant_
ROSCPP_DECL void spinOnce()
ROSCPP_DECL void shutdown()
void pidEnableCallback(const std_msgs::Bool &pid_enable_msg)
#define ROS_WARN_ONCE(...)
void publish(const boost::shared_ptr< M > &message) const
Publisher advertise(AdvertiseOptions &ops)
void plantStateCallback(const std_msgs::Float64 &state_msg)
std::string pid_debug_pub_name_
double min_loop_frequency_
#define ROS_WARN_STREAM(args)
std_msgs::Float64 control_msg_
ros::Publisher pid_debug_pub_
#define ROS_ASSERT_MSG(cond,...)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, const boost::function< void(C)> &callback, const VoidConstPtr &tracked_object=VoidConstPtr(), const TransportHints &transport_hints=TransportHints())
std::vector< double > filtered_error_
std::string topic_from_controller_
const ROSCPP_DECL std::string & getName()
std::string pid_enable_topic_
std::vector< double > error_deriv_
std::vector< double > filtered_error_deriv_
ros::Publisher control_effort_pub_
std::vector< double > error_
T param(const std::string ¶m_name, const T &default_val) const
std::string setpoint_topic_
double max_loop_frequency_
void setpointCallback(const std_msgs::Float64 &setpoint_msg)
bool validateParameters()
pid
Author(s): Andy Zelenak 
, Paul Bouchier
autogenerated on Wed Mar 2 2022 00:41:32