Skip to content

Commit 83d8c75

Browse files
destoglAndyZe
authored andcommitted
Last fix-ups
1 parent 511dbc9 commit 83d8c75

File tree

1 file changed

+4
-2
lines changed

1 file changed

+4
-2
lines changed

ur_controllers/src/scaled_joint_trajectory_controller.cpp

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -89,7 +89,8 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
8989
resize_joint_trajectory_point(state_current, joint_num);
9090

9191
// current state update
92-
for (auto index = 0ul; index < joint_num; ++index) {
92+
for (size_t index = 0; index < joint_num; ++index)
93+
{
9394
state_current.positions[index] = joint_position_state_interface_[index].get().get_value();
9495
state_current.velocities[index] = joint_velocity_state_interface_[index].get().get_value();
9596
state_current.accelerations[index] = 0.0;
@@ -123,7 +124,8 @@ controller_interface::return_type ScaledJointTrajectoryController::update()
123124
bool abort = false;
124125
bool outside_goal_tolerance = false;
125126
const bool before_last_point = end_segment_itr != (*traj_point_active_ptr_)->end();
126-
for (auto index = 0ul; index < joint_num; ++index) {
127+
for (size_t index = 0; index < joint_num; ++index)
128+
{
127129
// set values for next hardware write()
128130
joint_position_command_interface_[index].get().set_value(state_desired.positions[index]);
129131
compute_error_for_joint(state_error, index, state_current, state_desired);

0 commit comments

Comments
 (0)