Skip to content

Commit

Permalink
Revert "const& in publish_pid_state"
Browse files Browse the repository at this point in the history
This reverts commit ee356de.
  • Loading branch information
christophfroehlich committed Jan 28, 2025
1 parent 15c94a4 commit c607dda
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 @@ -407,7 +407,7 @@ class PidROS

void set_parameter_event_callback();

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

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

Expand Down
2 changes: 1 addition & 1 deletion src/pid_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -269,7 +269,7 @@ void PidROS::set_gains(double p, double i, double d, double i_max, double i_min,
}
}

void PidROS::publish_pid_state(double cmd, double error, const rclcpp::Duration & dt)
void PidROS::publish_pid_state(double cmd, double error, rclcpp::Duration dt)
{
Pid::Gains gains = pid_.get_gains();

Expand Down

0 comments on commit c607dda

Please sign in to comment.