Skip to content

Commit ac45c7a

Browse files
author
Michael Wiznitzer
committed
Revert "Fix JTC from immediately returning success (ros-controls#565)"
This reverts commit 634e6fe.
1 parent c37dfe6 commit ac45c7a

File tree

1 file changed

+0
-6
lines changed

1 file changed

+0
-6
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 0 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -163,8 +163,6 @@ controller_interface::return_type JointTrajectoryController::update(
163163
sort_to_local_joint_order(*new_external_msg);
164164
// TODO(denis): Add here integration of position and velocity
165165
traj_external_point_ptr_->update(*new_external_msg);
166-
// set the active trajectory pointer to the new goal
167-
traj_point_active_ptr_ = &traj_external_point_ptr_;
168166
}
169167

170168
// TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
@@ -321,8 +319,6 @@ controller_interface::return_type JointTrajectoryController::update(
321319
// TODO(matthew-reynolds): Need a lock-free write here
322320
// See https://github.com/ros-controls/ros2_controllers/issues/168
323321
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
324-
// remove the active trajectory pointer so that we stop commanding the hardware
325-
traj_point_active_ptr_ = nullptr;
326322

327323
// check goal tolerance
328324
}
@@ -336,8 +332,6 @@ controller_interface::return_type JointTrajectoryController::update(
336332
// TODO(matthew-reynolds): Need a lock-free write here
337333
// See https://github.com/ros-controls/ros2_controllers/issues/168
338334
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
339-
// remove the active trajectory pointer so that we stop commanding the hardware
340-
traj_point_active_ptr_ = nullptr;
341335

342336
RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!");
343337
}

0 commit comments

Comments
 (0)