Skip to content

Commit bceaf96

Browse files
Remove reactivation test from ROS 1
1 parent 7bc67e5 commit bceaf96

File tree

1 file changed

+2
-15
lines changed

1 file changed

+2
-15
lines changed

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 2 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -317,25 +317,12 @@ TEST_P(TrajectoryControllerTestParameterized, correct_initialization_using_param
317317
// reactivated
318318
// wait so controller process the third point when reactivated
319319
std::this_thread::sleep_for(std::chrono::milliseconds(3000));
320-
// TODO(anyone) test copied from ROS 1: it fails now!
321-
// should the old trajectory really be processed after reactivation?
322-
#if 0
323320
ActivateTrajectoryController();
324321
state = traj_controller_->get_state();
325322
ASSERT_EQ(state.id(), State::PRIMARY_STATE_ACTIVE);
326323

327-
updateController(rclcpp::Duration::from_seconds(0.5));
328-
// traj_controller_->update(
329-
// rclcpp::Time(static_cast<uint64_t>(0.75 * 1e9)), rclcpp::Duration::from_seconds(0.01));
330-
331-
// change in hw position to 3rd point
332-
if (traj_controller_->has_position_command_interface())
333-
{
334-
EXPECT_NEAR(10.10, joint_pos_[0], allowed_delta);
335-
EXPECT_NEAR(11.11, joint_pos_[1], allowed_delta);
336-
EXPECT_NEAR(12.12, joint_pos_[2], allowed_delta);
337-
}
338-
#endif
324+
// TODO(christophfroehlich) add test if there is no active trajectory after
325+
// reactivation once #558 or #609 got merged (needs methods for TestableJointTrajectoryController)
339326

340327
executor.cancel();
341328
}

0 commit comments

Comments
 (0)