Skip to content

Commit 3edfe5e

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

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
@@ -152,8 +152,6 @@ controller_interface::return_type JointTrajectoryController::update(
152152
sort_to_local_joint_order(*new_external_msg);
153153
// TODO(denis): Add here integration of position and velocity
154154
traj_external_point_ptr_->update(*new_external_msg);
155-
// set the active trajectory pointer to the new goal
156-
traj_point_active_ptr_ = &traj_external_point_ptr_;
157155
}
158156

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

323319
// check goal tolerance
324320
}
@@ -332,8 +328,6 @@ controller_interface::return_type JointTrajectoryController::update(
332328
// TODO(matthew-reynolds): Need a lock-free write here
333329
// See https://github.com/ros-controls/ros2_controllers/issues/168
334330
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
335-
// remove the active trajectory pointer so that we stop commanding the hardware
336-
traj_point_active_ptr_ = nullptr;
337331

338332
RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!");
339333
}

0 commit comments

Comments
 (0)