66 template <
class NodeT>
67 explicit PidROS(std::shared_ptr<NodeT> node_ptr, std::string topic_prefix = std::string(
""))
69 node_ptr->get_node_base_interface(), node_ptr->get_node_logging_interface(),
70 node_ptr->get_node_parameters_interface(), node_ptr->get_node_topics_interface(),
76 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
77 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
78 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
79 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
80 std::string topic_prefix = std::string(
""))
81 : node_base_(node_base),
82 node_logging_(node_logging),
83 node_params_(node_params),
84 topics_interface_(topics_interface)
86 initialize(topic_prefix);
98 void initPid(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup);
121 double computeCommand(
double error, rclcpp::Duration dt);
134 double computeCommand(
double error,
double error_dot, rclcpp::Duration dt);
140 Pid::Gains getGains();
151 void setGains(
double p,
double i,
double d,
double i_max,
double i_min,
bool antiwindup =
false);
157 void setGains(
const Pid::Gains & gains);
163 void setCurrentCmd(
double cmd);
169 double getCurrentCmd();
175 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> getPidStatePublisher();
183 void getCurrentPIDErrors(
double & pe,
double & ie,
double & de);
194 inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
197 return parameter_callback_;
201 void setParameterEventCallback();
203 void publishPIDState(
double cmd,
double error, rclcpp::Duration dt);
205 void declareParam(
const std::string & param_name, rclcpp::ParameterValue param_value);
207 bool getDoubleParam(
const std::string & param_name,
double & value);
209 bool getBooleanParam(
const std::string & param_name,
bool & value);
211 void initialize(std::string topic_prefix);
213 rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;
215 rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
216 rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
217 rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
218 rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;
220 std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
221 std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;
224 std::string topic_prefix_;
225 std::string param_prefix_;