diff --git a/Universal_Robots_ROS2_Driver-not-released.humble.repos b/Universal_Robots_ROS2_Driver-not-released.humble.repos index f1f74842e..2883541e6 100644 --- a/Universal_Robots_ROS2_Driver-not-released.humble.repos +++ b/Universal_Robots_ROS2_Driver-not-released.humble.repos @@ -4,3 +4,7 @@ # Once Upstream packages are released and synced to the target distributions in the required # version, the entry in this file shall be removed again. repositories: + ros2_controllers: + type: git + url: https://github.com/ros-controls/ros2_controllers + version: 2.14.0 diff --git a/Universal_Robots_ROS2_Driver.humble.repos b/Universal_Robots_ROS2_Driver.humble.repos index 1ccf74a37..f9e948e30 100644 --- a/Universal_Robots_ROS2_Driver.humble.repos +++ b/Universal_Robots_ROS2_Driver.humble.repos @@ -14,7 +14,7 @@ repositories: ros2_controllers: type: git url: https://github.com/ros-controls/ros2_controllers - version: 2.12.0 + version: master kinematics_interface: type: git url: https://github.com/ros-controls/kinematics_interface.git diff --git a/ur_controllers/src/scaled_joint_trajectory_controller.cpp b/ur_controllers/src/scaled_joint_trajectory_controller.cpp index acfe0bdb6..ae7616126 100644 --- a/ur_controllers/src/scaled_joint_trajectory_controller.cpp +++ b/ur_controllers/src/scaled_joint_trajectory_controller.cpp @@ -106,7 +106,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const } JointTrajectoryPoint state_current, state_desired, state_error; - const auto joint_num = joint_names_.size(); + const auto joint_num = params_.joints.size(); resize_joint_trajectory_point(state_current, joint_num); // current state update @@ -206,7 +206,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const // send feedback auto feedback = std::make_shared(); feedback->header.stamp = time; - feedback->joint_names = joint_names_; + feedback->joint_names = params_.joints; feedback->actual = state_current; feedback->desired = state_desired;