From 34ec02ea67827d651c524e0a66c8dcd8ebaa7cbc Mon Sep 17 00:00:00 2001 From: Christoph Froehlich Date: Wed, 15 Nov 2023 17:13:29 +0000 Subject: [PATCH] Rename read_state_from_hardware method Co-authored-by: Dr. Denis --- .../joint_trajectory_controller.hpp | 2 +- .../src/joint_trajectory_controller.cpp | 10 +++++----- 2 files changed, 6 insertions(+), 6 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 0dbd42121d..eaf821aa26 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 @@ -261,7 +261,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa const rclcpp::Time & time, const JointTrajectoryPoint & desired_state, const JointTrajectoryPoint & current_state, const JointTrajectoryPoint & state_error); - void read_state_from_hardware(JointTrajectoryPoint & state); + void read_state_from_state_interfaces(JointTrajectoryPoint & state); /** Assign values from the command interfaces as state. * This is only possible if command AND state interfaces exist for the same type, diff --git a/joint_trajectory_controller/src/joint_trajectory_controller.cpp b/joint_trajectory_controller/src/joint_trajectory_controller.cpp index d37a0444f9..1c2c31f4d1 100644 --- a/joint_trajectory_controller/src/joint_trajectory_controller.cpp +++ b/joint_trajectory_controller/src/joint_trajectory_controller.cpp @@ -175,7 +175,7 @@ controller_interface::return_type JointTrajectoryController::update( // current state update state_current_.time_from_start.set__sec(0); - read_state_from_hardware(state_current_); + read_state_from_state_interfaces(state_current_); // currently carrying out a trajectory if (has_active_trajectory()) @@ -397,7 +397,7 @@ controller_interface::return_type JointTrajectoryController::update( return controller_interface::return_type::OK; } -void JointTrajectoryController::read_state_from_hardware(JointTrajectoryPoint & state) +void JointTrajectoryController::read_state_from_state_interfaces(JointTrajectoryPoint & state) { auto assign_point_from_interface = [&](std::vector & trajectory_point_interface, const auto & joint_interface) @@ -965,9 +965,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate( else { // Initialize current state storage from hardware - read_state_from_hardware(state_current_); - read_state_from_hardware(state_desired_); - read_state_from_hardware(last_commanded_state_); + read_state_from_state_interfaces(state_current_); + read_state_from_state_interfaces(state_desired_); + read_state_from_state_interfaces(last_commanded_state_); } // Should the controller start by holding position at the beginning of active state?