Skip to content

Commit c8cf278

Browse files
set_hold_position on success
1 parent 8e88c4d commit c8cf278

File tree

1 file changed

+1
-0
lines changed

1 file changed

+1
-0
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+1
Original file line numberDiff line numberDiff line change
@@ -328,6 +328,7 @@ controller_interface::return_type JointTrajectoryController::update(
328328
{
329329
if (!outside_goal_tolerance)
330330
{
331+
set_hold_position();
331332
auto res = std::make_shared<FollowJTrajAction::Result>();
332333
res->set__error_code(FollowJTrajAction::Result::SUCCESSFUL);
333334
active_goal->setSucceeded(res);

0 commit comments

Comments
 (0)