@@ -40,43 +40,15 @@ constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR;
40
40
41
41
void ForceTorqueSensorBroadcasterTest::SetUpTestCase () {}
42
42
43
- void ForceTorqueSensorBroadcasterTest::TearDownTestCase ()
44
- {
45
- // Ensure all nodes are properly shutdown
46
- rclcpp::shutdown ();
47
- // Add a small delay to allow proper cleanup
48
- std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
49
- }
43
+ void ForceTorqueSensorBroadcasterTest::TearDownTestCase () {}
50
44
51
45
void ForceTorqueSensorBroadcasterTest::SetUp ()
52
46
{
53
47
// initialize controller
54
48
fts_broadcaster_ = std::make_unique<FriendForceTorqueSensorBroadcaster>();
55
49
}
56
50
57
- void ForceTorqueSensorBroadcasterTest::TearDown ()
58
- {
59
- // Reset the broadcaster with proper cleanup
60
- if (fts_broadcaster_)
61
- {
62
- if (
63
- fts_broadcaster_->get_lifecycle_state ().id () !=
64
- lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
65
- {
66
- if (
67
- fts_broadcaster_->get_lifecycle_state ().id () ==
68
- lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
69
- {
70
- ASSERT_EQ (fts_broadcaster_->on_deactivate (rclcpp_lifecycle::State ()), NODE_SUCCESS);
71
- }
72
- // Clean up the broadcaster
73
- ASSERT_EQ (fts_broadcaster_->on_cleanup (rclcpp_lifecycle::State ()), NODE_SUCCESS);
74
- }
75
- fts_broadcaster_.reset (nullptr );
76
- }
77
- // Add a small delay between tests
78
- std::this_thread::sleep_for (std::chrono::milliseconds (50 ));
79
- }
51
+ void ForceTorqueSensorBroadcasterTest::TearDown () { fts_broadcaster_.reset (nullptr ); }
80
52
81
53
void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster ()
82
54
{
0 commit comments