@@ -242,7 +242,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_single_point_sendgoa
242242 EXPECT_EQ (rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
243243
244244 // run an update
245- updateController (rclcpp::Duration::from_seconds (0.01 ));
245+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
246246
247247 // it should be holding the last position goal
248248 // i.e., active but trivial trajectory (one point only)
@@ -298,7 +298,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_success_multi_point_sendgoal
298298 EXPECT_EQ (rclcpp_action::ResultCode::SUCCEEDED, common_resultcode_);
299299
300300 // run an update
301- updateController (rclcpp::Duration::from_seconds (0.01 ));
301+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
302302
303303 // it should be holding the last position goal
304304 // i.e., active but trivial trajectory (one point only)
@@ -350,7 +350,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_single_point_success)
350350 control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);
351351
352352 // run an update
353- updateController (rclcpp::Duration::from_seconds (0.01 ));
353+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
354354
355355 // it should be holding the last position goal
356356 // i.e., active but trivial trajectory (one point only)
@@ -409,7 +409,7 @@ TEST_F(TestTrajectoryActions, test_goal_tolerances_multi_point_success)
409409 control_msgs::action::FollowJointTrajectory_Result::SUCCESSFUL, common_action_result_code_);
410410
411411 // run an update
412- updateController (rclcpp::Duration::from_seconds (0.01 ));
412+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
413413
414414 // it should be holding the last position goal
415415 // i.e., active but trivial trajectory (one point only)
@@ -460,7 +460,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_state_tolerances_fail)
460460 common_action_result_code_);
461461
462462 // run an update
463- updateController (rclcpp::Duration::from_seconds (0.01 ));
463+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
464464
465465 // it should be holding the position (being the initial one)
466466 // i.e., active but trivial trajectory (one point only)
@@ -509,7 +509,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_goal_tolerances_fail)
509509 common_action_result_code_);
510510
511511 // run an update
512- updateController (rclcpp::Duration::from_seconds (0.01 ));
512+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
513513
514514 // it should be holding the position (being the initial one)
515515 // i.e., active but trivial trajectory (one point only)
@@ -555,7 +555,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_no_time_from_start_state_tol
555555 common_action_result_code_);
556556
557557 // run an update
558- updateController (rclcpp::Duration::from_seconds (0.01 ));
558+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
559559
560560 // it should be holding the position (being the initial one)
561561 // i.e., active but trivial trajectory (one point only)
@@ -603,7 +603,7 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_cancel_hold_position)
603603 std::vector<double > cancelled_position{joint_pos_[0 ], joint_pos_[1 ], joint_pos_[2 ]};
604604
605605 // run an update
606- updateController (rclcpp::Duration::from_seconds (0.01 ));
606+ updateControllerAsync (rclcpp::Duration::from_seconds (0.01 ));
607607
608608 // it should be holding the last position,
609609 // i.e., active but trivial trajectory (one point only)
0 commit comments