Skip to content

Commit 588c5b8

Browse files
author
Felix Exner (fexner)
authored
Ros2 controllers 2.14 (#547)
* Require ros2_controllers 2.14 for binary build and master for semi-binary * Re-Add "Adapt jtc controller params to new param api" This was removed due to release problems, but we should get back to the latest ros2_controllers compatibility.
1 parent 47a2fc0 commit 588c5b8

File tree

3 files changed

+7
-3
lines changed

3 files changed

+7
-3
lines changed

Universal_Robots_ROS2_Driver-not-released.humble.repos

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,3 +4,7 @@
44
# Once Upstream packages are released and synced to the target distributions in the required
55
# version, the entry in this file shall be removed again.
66
repositories:
7+
ros2_controllers:
8+
type: git
9+
url: https://github.com/ros-controls/ros2_controllers
10+
version: 2.14.0

Universal_Robots_ROS2_Driver.humble.repos

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -14,7 +14,7 @@ repositories:
1414
ros2_controllers:
1515
type: git
1616
url: https://github.com/ros-controls/ros2_controllers
17-
version: 2.12.0
17+
version: master
1818
kinematics_interface:
1919
type: git
2020
url: https://github.com/ros-controls/kinematics_interface.git

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -106,7 +106,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
106106
}
107107

108108
JointTrajectoryPoint state_current, state_desired, state_error;
109-
const auto joint_num = joint_names_.size();
109+
const auto joint_num = params_.joints.size();
110110
resize_joint_trajectory_point(state_current, joint_num);
111111

112112
// current state update
@@ -206,7 +206,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
206206
// send feedback
207207
auto feedback = std::make_shared<FollowJTrajAction::Feedback>();
208208
feedback->header.stamp = time;
209-
feedback->joint_names = joint_names_;
209+
feedback->joint_names = params_.joints;
210210

211211
feedback->actual = state_current;
212212
feedback->desired = state_desired;

0 commit comments

Comments
 (0)