Skip to content

Commit e9d63ff

Browse files
destoglMGBla
authored andcommitted
Correct formating, include std::vector and update ros2_controller to master branch in repo file.
1 parent bb43b9b commit e9d63ff

File tree

2 files changed

+26
-27
lines changed

2 files changed

+26
-27
lines changed

Universal_Robots_ROS2_Driver.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.git
17-
version: 0.2.1
17+
version: master
1818
Universal_Robots_Client_Library:
1919
type: git
2020
url: https://github.com/UniversalRobots/Universal_Robots_Client_Library.git

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 25 additions & 26 deletions
Original file line numberDiff line numberDiff line change
@@ -22,6 +22,7 @@
2222
//----------------------------------------------------------------------
2323

2424
#include <memory>
25+
#include <vector>
2526

2627
#include "ur_controllers/scaled_joint_trajectory_controller.hpp"
2728

@@ -61,22 +62,22 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
6162
auto resize_joint_trajectory_point = [&](trajectory_msgs::msg::JointTrajectoryPoint& point, size_t size) {
6263
point.positions.resize(size);
6364
if (has_velocity_state_interface_) {
64-
point.velocities.resize(size);
65-
}
66-
if (has_acceleration_state_interface_) {
67-
point.accelerations.resize(size);
68-
}
65+
point.velocities.resize(size);
66+
}
67+
if (has_acceleration_state_interface_) {
68+
point.accelerations.resize(size);
69+
}
6970
};
7071
auto compute_error_for_joint = [&](JointTrajectoryPoint& error, int index, const JointTrajectoryPoint& current,
71-
const JointTrajectoryPoint& desired) {
72+
const JointTrajectoryPoint& desired) {
7273
// error defined as the difference between current and desired
7374
error.positions[index] = angles::shortest_angular_distance(current.positions[index], desired.positions[index]);
74-
if (has_velocity_state_interface_ && has_velocity_command_interface_) {
75-
error.velocities[index] = desired.velocities[index] - current.velocities[index];
76-
}
77-
if (has_acceleration_state_interface_ && has_acceleration_command_interface_) {
78-
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index];
79-
}
75+
if (has_velocity_state_interface_ && has_velocity_command_interface_) {
76+
error.velocities[index] = desired.velocities[index] - current.velocities[index];
77+
}
78+
if (has_acceleration_state_interface_ && has_acceleration_command_interface_) {
79+
error.accelerations[index] = desired.accelerations[index] - current.accelerations[index];
80+
}
8081
};
8182

8283
// Check if a new external message has been received from nonRT threads
@@ -93,20 +94,18 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
9394
resize_joint_trajectory_point(state_current, joint_num);
9495

9596
// current state update
96-
auto assign_point_from_interface = [&, joint_num](
97-
std::vector<double> & trajectory_point_interface, const auto & joint_inteface)
98-
{
99-
for (auto index = 0ul; index < joint_num; ++index) {
100-
trajectory_point_interface[index] = joint_inteface[index].get().get_value();
101-
}
102-
};
103-
auto assign_interface_from_point = [&, joint_num](
104-
auto & joint_inteface, const std::vector<double> & trajectory_point_interface)
105-
{
106-
for (auto index = 0ul; index < joint_num; ++index) {
107-
joint_inteface[index].get().set_value(trajectory_point_interface[index]);
108-
}
109-
};
97+
auto assign_point_from_interface = [&, joint_num](std::vector<double>& trajectory_point_interface,
98+
const auto& joint_inteface) {
99+
for (auto index = 0ul; index < joint_num; ++index) {
100+
trajectory_point_interface[index] = joint_inteface[index].get().get_value();
101+
}
102+
};
103+
auto assign_interface_from_point = [&, joint_num](auto& joint_inteface,
104+
const std::vector<double>& trajectory_point_interface) {
105+
for (auto index = 0ul; index < joint_num; ++index) {
106+
joint_inteface[index].get().set_value(trajectory_point_interface[index]);
107+
}
108+
};
110109

111110
state_current.time_from_start.set__sec(0);
112111

0 commit comments

Comments
 (0)