Skip to content

Commit

Permalink
Added topic_prefix to publisher topic name (ros-controls#95)
Browse files Browse the repository at this point in the history
* Added topic_prefix to publisher topic name

Signed-off-by: ahcorde <[email protected]>

* make linters happy

Signed-off-by: ahcorde <[email protected]>
  • Loading branch information
ahcorde authored Jun 11, 2020
1 parent 22ef84f commit 3907e9d
Show file tree
Hide file tree
Showing 3 changed files with 17 additions and 16 deletions.
2 changes: 1 addition & 1 deletion include/control_toolbox/pid.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -206,7 +206,7 @@ class Pid
* \param node A pointer to the node.
*/

void initPublisher(NodePtr node);
void initPublisher(NodePtr node, std::string topic_prefix = "");

/*!
* \brief Reset the state of this PID controller
Expand Down
29 changes: 15 additions & 14 deletions src/pid.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -122,12 +122,12 @@ void Pid::initPid(double p, double i, double d, double i_max, double i_min, bool
reset();
}

void Pid::initPublisher(NodePtr node)
void Pid::initPublisher(NodePtr node, std::string topic_prefix)
{
rclcpp::QoS qos(10);
qos.reliable().transient_local();

state_pub_ = node->create_publisher<PidStateMsg>("state", qos);
state_pub_ = node->create_publisher<PidStateMsg>(topic_prefix + "/pid_state", qos);
rt_state_pub_.reset(
new realtime_tools::RealtimePublisher<control_msgs::msg::PidState>(state_pub_));

Expand Down Expand Up @@ -289,19 +289,20 @@ void Pid::printValues(const rclcpp::Logger & logger)
{
Gains gains = getGains();

RCLCPP_INFO_STREAM(logger,
RCLCPP_INFO_STREAM(
logger,
"Current Values of PID Class:\n" <<
" P Gain: " << gains.p_gain_ << "\n" <<
" I Gain: " << gains.i_gain_ << "\n" <<
" D Gain: " << gains.d_gain_ << "\n" <<
" I_Max: " << gains.i_max_ << "\n" <<
" I_Min: " << gains.i_min_ << "\n" <<
" Antiwindup: " << gains.antiwindup_ << "\n" <<
" P_Error_Last: " << p_error_last_ << "\n" <<
" P_Error: " << p_error_ << "\n" <<
" I_Error: " << i_error_ << "\n" <<
" D_Error: " << d_error_ << "\n" <<
" Command: " << cmd_
" P Gain: " << gains.p_gain_ << "\n" <<
" I Gain: " << gains.i_gain_ << "\n" <<
" D Gain: " << gains.d_gain_ << "\n" <<
" I_Max: " << gains.i_max_ << "\n" <<
" I_Min: " << gains.i_min_ << "\n" <<
" Antiwindup: " << gains.antiwindup_ << "\n" <<
" P_Error_Last: " << p_error_last_ << "\n" <<
" P_Error: " << p_error_ << "\n" <<
" I_Error: " << i_error_ << "\n" <<
" D_Error: " << d_error_ << "\n" <<
" Command: " << cmd_
);
}

Expand Down
2 changes: 1 addition & 1 deletion test/pid_publisher_tests.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ TEST(PidPublihserTest, PublishTest)
callback_called = true;
};

auto state_sub = node->create_subscription<PidStateMsg>("state", 10, state_callback);
auto state_sub = node->create_subscription<PidStateMsg>("pid_state", 10, state_callback);

double command = pid.computeCommand(-0.5, rclcpp::Duration(1, 0));
EXPECT_EQ(-1.5, command);
Expand Down

0 comments on commit 3907e9d

Please sign in to comment.