Skip to content

Commit

Permalink
Apply suggestions from code review
Browse files Browse the repository at this point in the history
Co-authored-by: Sai Kishor Kothakota <[email protected]>
  • Loading branch information
christophfroehlich and saikishor authored Dec 18, 2024
1 parent fc06593 commit 44a8734
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 2 deletions.
2 changes: 1 addition & 1 deletion include/control_toolbox/pid_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -368,7 +368,7 @@ class CONTROL_TOOLBOX_PUBLIC 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(std::string topic_prefix);
void set_prefixes(const std::string &topic_prefix);

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

Expand Down
2 changes: 1 addition & 1 deletion src/pid_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ PidROS::PidROS(
new realtime_tools::RealtimePublisher<control_msgs::msg::PidState>(state_pub_));
}

void PidROS::set_prefixes(std::string topic_prefix)
void PidROS::set_prefixes(const std::string &topic_prefix)
{
param_prefix_ = topic_prefix;
// If it starts with a "~", remove it
Expand Down

0 comments on commit 44a8734

Please sign in to comment.