Skip to content

Commit

Permalink
Revert "Don't use const&"
Browse files Browse the repository at this point in the history
This reverts commit 15c94a4.
  • Loading branch information
christophfroehlich committed Jan 29, 2025
1 parent c607dda commit 2a336f1
Show file tree
Hide file tree
Showing 2 changed files with 4 additions and 6 deletions.
6 changes: 2 additions & 4 deletions include/control_toolbox/pid_ros.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,8 +188,7 @@ class PidROS
*
* \returns PID command
*/
// TODO(christophfroehlich): add const& for duration -> breaks ABI
double compute_command(double error, rclcpp::Duration dt);
double compute_command(double error, const rclcpp::Duration & dt);

/*!
* \brief Set the PID error and compute the PID command with nonuniform time
Expand All @@ -215,8 +214,7 @@ class PidROS
*
* \returns PID command
*/
// TODO(christophfroehlich): add const& for duration -> breaks ABI
double compute_command(double error, double error_dot, rclcpp::Duration dt);
double compute_command(double error, double error_dot, const rclcpp::Duration & dt);

/*!
* \brief Set the PID error and compute the PID command with nonuniform
Expand Down
4 changes: 2 additions & 2 deletions src/pid_ros.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -237,14 +237,14 @@ std::shared_ptr<rclcpp::Publisher<control_msgs::msg::PidState>> PidROS::get_pid_
return state_pub_;
}

double PidROS::compute_command(double error, rclcpp::Duration dt)
double PidROS::compute_command(double error, const rclcpp::Duration & dt)
{
double cmd = pid_.compute_command(error, dt);
publish_pid_state(cmd, error, dt);
return cmd;
}

double PidROS::compute_command(double error, double error_dot, rclcpp::Duration dt)
double PidROS::compute_command(double error, double error_dot, const rclcpp::Duration & dt)
{
double cmd = pid_.compute_command(error, error_dot, dt);
publish_pid_state(cmd, error, dt);
Expand Down

0 comments on commit 2a336f1

Please sign in to comment.