Program Listing for File pid_ros.hpp

Return to documentation for file (include/control_toolbox/pid_ros.hpp)

// Copyright (c) 2020, Open Source Robotics Foundation, Inc.
// All rights reserved.
//
// Software License Agreement (BSD License 2.0)
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions
// are met:
//
//  * Redistributions of source code must retain the above copyright
//    notice, this list of conditions and the following disclaimer.
//  * Redistributions in binary form must reproduce the above
//    copyright notice, this list of conditions and the following
//    disclaimer in the documentation and/or other materials provided
//    with the distribution.
//  * Neither the name of the Willow Garage nor the names of its
//    contributors may be used to endorse or promote products derived
//    from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.

#ifndef CONTROL_TOOLBOX__PID_ROS_HPP_
#define CONTROL_TOOLBOX__PID_ROS_HPP_

#include <memory>
#include <string>

#include "control_msgs/msg/pid_state.hpp"

#include "rclcpp/clock.hpp"
#include "rclcpp/duration.hpp"
#include "rclcpp/node.hpp"

#include "realtime_tools/realtime_buffer.hpp"
#include "realtime_tools/realtime_publisher.hpp"

#include "control_toolbox/pid.hpp"

namespace control_toolbox
{

class PidROS
{
public:
  template <class NodeT>
  explicit PidROS(
    std::shared_ptr<NodeT> node_ptr, std::string prefix = std::string(""),
    bool prefix_is_for_params = false)
  : PidROS(
      node_ptr->get_node_base_interface(), node_ptr->get_node_logging_interface(),
      node_ptr->get_node_parameters_interface(), node_ptr->get_node_topics_interface(), prefix,
      prefix_is_for_params)
  {
  }

  PidROS(
    rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base,
    rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging,
    rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params,
    rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface,
    std::string prefix = std::string(""), bool prefix_is_for_params = false);

  [[deprecated("Use initialize_from_args with AntiwindupStrategy instead.")]]
  void initialize_from_args(
    double p, double i, double d, double i_max, double i_min, bool antiwindup);

  [[deprecated("Use initialize_from_args with AntiwindupStrategy instead.")]]
  void initialize_from_args(
    double p, double i, double d, double i_max, double i_min, bool antiwindup, bool save_i_term);

  [[deprecated("Use initialize_from_args with AntiwindupStrategy only.")]]
  void initialize_from_args(
    double p, double i, double d, double i_max, double i_min, double u_max, double u_min,
    double trk_tc, bool saturation, bool antiwindup, AntiwindupStrategy antiwindup_strat,
    bool save_i_term);

  void initialize_from_args(
    double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation,
    AntiwindupStrategy antiwindup_strat, bool save_i_term);

  bool initialize_from_ros_parameters();

  void reset();

  void reset(bool save_i_term);

  double compute_command(double error, const rclcpp::Duration & dt);

  double compute_command(double error, double error_dot, const rclcpp::Duration & dt);

  Pid::Gains get_gains();

  [[deprecated("Use set_gains with AntiwindupStrategy instead.")]]
  void set_gains(double p, double i, double d, double i_max, double i_min, bool antiwindup = false);

  [[deprecated("Use set_gains with AntiwindupStrategy only.")]]
  void set_gains(
    double p, double i, double d, double i_max, double i_min, double u_max, double u_min,
    double trk_tc = 0.0, bool saturation = false, bool antiwindup = false,
    AntiwindupStrategy antiwindup_strat = AntiwindupStrategy::NONE);

  void set_gains(
    double p, double i, double d, double u_max, double u_min, double trk_tc, bool saturation,
    AntiwindupStrategy antiwindup_strat);

  void set_gains(const Pid::Gains & gains);

  void set_current_cmd(double cmd);

  double get_current_cmd();

  std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> get_pid_state_publisher();

  void get_current_pid_errors(double & pe, double & ie, double & de);

  void print_values();

  inline rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr
  get_parameters_callback_handle()
  {
    return parameter_callback_;
  }

protected:
  std::string topic_prefix_;
  std::string param_prefix_;

private:
  void set_parameter_event_callback();

  void publish_pid_state(double cmd, double error, rclcpp::Duration dt);

  void declare_param(const std::string & param_name, rclcpp::ParameterValue param_value);

  bool get_double_param(const std::string & param_name, double & value);

  bool get_boolean_param(const std::string & param_name, bool & value);

  bool get_string_param(const std::string & param_name, std::string & value);

  void set_prefixes(const std::string & topic_prefix);

  rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr parameter_callback_;

  rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base_;
  rclcpp::node_interfaces::NodeLoggingInterface::SharedPtr node_logging_;
  rclcpp::node_interfaces::NodeParametersInterface::SharedPtr node_params_;
  rclcpp::node_interfaces::NodeTopicsInterface::SharedPtr topics_interface_;

  std::shared_ptr<realtime_tools::RealtimePublisher<control_msgs::msg::PidState>> rt_state_pub_;
  std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> state_pub_;

  Pid pid_;
};

}  // namespace control_toolbox

#endif  // CONTROL_TOOLBOX__PID_ROS_HPP_