Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
76 changes: 73 additions & 3 deletions control_toolbox/include/control_toolbox/pid_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ class PidROS
*
*/
template <class NodeT>
explicit PidROS(
[[deprecated("Use overloads with explicit prefixes for params and topics")]] explicit PidROS(
std::shared_ptr<NodeT> node_ptr, std::string prefix = std::string(""),
bool prefix_is_for_params = false)
: PidROS(
Expand All @@ -77,14 +77,84 @@ class PidROS
prefix_is_for_params)
{
}
template <class NodeT>
explicit PidROS(std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix)
: 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(),
param_prefix, "", false)
{
}
/*!
* \brief Constructor of PidROS class.
*
* The node is passed to this class to handler the ROS parameters, this class allows
* to add a prefix to the pid parameters
*
* \param node Any ROS node
* \param param_prefix prefix to add to the pid parameters.
* \param topic_prefix prefix to add to the state publisher. If it starts with `~/`, topic will be local under the namespace of the node. If it starts with `/` or an alphanumeric character, topic will be in global namespace.
*
*/
template <class NodeT>
explicit PidROS(
std::shared_ptr<NodeT> node_ptr, const std::string & param_prefix,
const std::string & topic_prefix)
: 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(),
param_prefix, topic_prefix, true)
{
}
/*!
* \brief Constructor of PidROS class.
*
* The node is passed to this class to handler the ROS parameters, this class allows
* to add a prefix to the pid parameters
*
* \param node Any ROS node
* \param param_prefix prefix to add to the pid parameters.
* \param topic_prefix prefix to add to the state publisher. If it starts with `~/`, topic will be local under the namespace of the node. If it starts with `/` or an alphanumeric character, topic will be in global namespace.
* \param activate_state_publisher If true, the publisher will be enabled after initialization.
*
*/
template <class NodeT>
explicit PidROS(
std::shared_ptr<NodeT> node_ptr, std::string param_prefix, std::string topic_prefix,
bool activate_state_publisher)
: 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(),
param_prefix, topic_prefix, activate_state_publisher)
{
}

PidROS(
[[deprecated("Use overloads with explicit prefixes for params and topics")]] 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);

/*!
* \brief Constructor of PidROS class with node_interfaces
*
* \param node_base Node base interface pointer.
* \param node_logging Node logging interface pointer.
* \param node_params Node parameters interface pointer.
* \param topics_interface Node topics interface pointer.
* \param param_prefix Prefix to add to the PID parameters. This string is not manipulated, i.e., probably should end with `.`.
* \param topic_prefix Prefix to add to the state publisher. This string is not manipulated, i.e., probably should end with `/`. If it starts with `~/`, topic will be local under the namespace of the node. If it starts with `/` or an alphanumeric character, topic will be in global namespace.
* \param activate_state_publisher If true, the publisher will be enabled after initialization.
*/
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,
const std::string & param_prefix, const std::string & topic_prefix,
bool activate_state_publisher);

/*!
* \brief Initialize the PID controller and set the parameters
* \param p The proportional gain.
Expand Down Expand Up @@ -473,7 +543,7 @@ class PidROS
* If not stated explicitly using "/" or "~", prefix is interpreted as global, i.e.,
* "/" will be added in front of topic prefix
*/
void set_prefixes(const std::string & topic_prefix);
[[deprecated]] void set_prefixes(const std::string & topic_prefix);

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

Expand Down
62 changes: 61 additions & 1 deletion control_toolbox/src/pid_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,12 @@ PidROS::PidROS(
node_params_(node_params),
topics_interface_(topics_interface)
{
// note: deprecation on templated constructor does not show up
RCLCPP_WARN(
node_logging->get_logger(),
"PidROS constructor with node and prefix is deprecated, use overloads with explicit "
"prefixes for params and topics");

if (prefix_is_for_params)
{
param_prefix_ = prefix;
Expand Down Expand Up @@ -97,6 +103,39 @@ PidROS::PidROS(
rt_state_pub_.reset(
new realtime_tools::RealtimePublisher<control_msgs::msg::PidState>(state_pub_));
}

PidROS::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,
const std::string & param_prefix, const std::string & topic_prefix, bool activate_state_publisher)
: topic_prefix_(topic_prefix),
param_prefix_(param_prefix),
node_base_(node_base),
node_logging_(node_logging),
node_params_(node_params),
topics_interface_(topics_interface)
{
// Add a trailing "."
if (!param_prefix_.empty() && param_prefix_.back() != '.')
{
param_prefix_.append(".");
}
// Add a trailing "/"
if (!topic_prefix_.empty() && topic_prefix_.back() != '/')
{
topic_prefix_.append("/");
}

if (activate_state_publisher)
{
state_pub_ = rclcpp::create_publisher<control_msgs::msg::PidState>(
topics_interface_, topic_prefix_ + "pid_state", rclcpp::SensorDataQoS());
rt_state_pub_.reset(
new realtime_tools::RealtimePublisher<control_msgs::msg::PidState>(state_pub_));
}
}
#pragma GCC diagnostic pop

void PidROS::set_prefixes(const std::string & topic_prefix)
Expand Down Expand Up @@ -329,7 +368,6 @@ bool PidROS::initialize_from_args(
if (pid_.initialize(p, i, d, u_max, u_min, antiwindup_strat))
{
const Pid::Gains gains = pid_.get_gains();

declare_param(param_prefix_ + "p", rclcpp::ParameterValue(gains.p_gain_));
declare_param(param_prefix_ + "i", rclcpp::ParameterValue(gains.i_gain_));
declare_param(param_prefix_ + "d", rclcpp::ParameterValue(gains.d_gain_));
Expand All @@ -352,6 +390,9 @@ bool PidROS::initialize_from_args(
param_prefix_ + "antiwindup_strategy",
rclcpp::ParameterValue(gains.antiwindup_strat_.to_string()));
declare_param(param_prefix_ + "save_i_term", rclcpp::ParameterValue(save_i_term));
declare_param(
param_prefix_ + "activate_state_publisher",
rclcpp::ParameterValue(rt_state_pub_ != nullptr));

set_parameter_event_callback();
return true;
Expand Down Expand Up @@ -636,6 +677,25 @@ void PidROS::set_parameter_event_callback()
gains.antiwindup_strat_.error_deadband = parameter.get_value<double>();
changed = true;
}
else if (param_name == param_prefix_ + "activate_state_publisher")
{
if (parameter.get_value<bool>())
{
std::string topic_name = topic_prefix_ + "pid_state";
RCLCPP_INFO(
node_logging_->get_logger(), "Activate publisher: `%s` ...", topic_name.c_str());
state_pub_ = rclcpp::create_publisher<control_msgs::msg::PidState>(
topics_interface_, topic_name, rclcpp::SensorDataQoS());
rt_state_pub_.reset(
new realtime_tools::RealtimePublisher<control_msgs::msg::PidState>(state_pub_));
}
else
{
RCLCPP_INFO(node_logging_->get_logger(), "Deactivate publisher...");
state_pub_.reset();
rt_state_pub_.reset();
}
}
}
catch (const rclcpp::exceptions::InvalidParameterTypeException & e)
{
Expand Down
Loading