From 6f67f65ea8ae64aa7c0b45bee1ab895409ccf67b Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Fri, 22 Dec 2023 17:37:25 +0000 Subject: [PATCH] Make reference_wrapper argument const --- .../joint_trajectory_controller.hpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp index e515922c1c..3cc4293219 100644 --- a/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp +++ b/joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp @@ -309,20 +309,17 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa void resize_joint_trajectory_point_command( trajectory_msgs::msg::JointTrajectoryPoint & point, size_t size); - // TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not - // changed, but its value only? - // TODO(anyone): Use auto in parameter declaration with c++20 - /** * @brief Assigns the values from a trajectory point interface to a joint interface. * * @tparam T The type of the joint interface. * @param[out] joint_interface The reference_wrapper to assign the values to * @param[in] trajectory_point_interface Containing the values to assign. + * @todo: Use auto in parameter declaration with c++20 */ template void assign_interface_from_point( - T & joint_interface, const std::vector & trajectory_point_interface) + const T & joint_interface, const std::vector & trajectory_point_interface) { for (size_t index = 0; index < dof_; ++index) {