2525#include " force_torque_sensor_broadcaster/force_torque_sensor_broadcaster.hpp"
2626#include " geometry_msgs/msg/wrench_stamped.hpp"
2727#include " hardware_interface/loaned_state_interface.hpp"
28+ <<<<<<< HEAD
2829#include " hardware_interface/types/hardware_interface_return_values.hpp"
2930#include " hardware_interface/types/hardware_interface_type_values.hpp"
3031#include " lifecycle_msgs/msg/state.hpp"
3132#include " rclcpp/utilities.hpp"
3233#include " rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp"
3334
35+ =======
36+ #include " lifecycle_msgs/msg/state.hpp"
37+ #include " rclcpp/executor.hpp"
38+ #include " rclcpp/executors.hpp"
39+ #include " rclcpp/utilities.hpp"
40+ >>>>>>> 996f030 ([CI] Time out from test_force_torque_sensor_broadcaster (#1586 ))
3441using hardware_interface::LoanedStateInterface;
3542using testing::IsEmpty;
3643using testing::SizeIs;
@@ -43,15 +50,43 @@ constexpr auto NODE_ERROR = controller_interface::CallbackReturn::ERROR;
4350
4451void ForceTorqueSensorBroadcasterTest::SetUpTestCase () {}
4552
46- void ForceTorqueSensorBroadcasterTest::TearDownTestCase () {}
53+ void ForceTorqueSensorBroadcasterTest::TearDownTestCase ()
54+ {
55+ // Ensure all nodes are properly shutdown
56+ rclcpp::shutdown ();
57+ // Add a small delay to allow proper cleanup
58+ std::this_thread::sleep_for (std::chrono::milliseconds (100 ));
59+ }
4760
4861void ForceTorqueSensorBroadcasterTest::SetUp ()
4962{
5063 // initialize controller
5164 fts_broadcaster_ = std::make_unique<FriendForceTorqueSensorBroadcaster>();
5265}
5366
54- void ForceTorqueSensorBroadcasterTest::TearDown () { fts_broadcaster_.reset (nullptr ); }
67+ void ForceTorqueSensorBroadcasterTest::TearDown ()
68+ {
69+ // Reset the broadcaster with proper cleanup
70+ if (fts_broadcaster_)
71+ {
72+ if (
73+ fts_broadcaster_->get_lifecycle_state ().id () !=
74+ lifecycle_msgs::msg::State::PRIMARY_STATE_UNCONFIGURED)
75+ {
76+ if (
77+ fts_broadcaster_->get_lifecycle_state ().id () ==
78+ lifecycle_msgs::msg::State::PRIMARY_STATE_ACTIVE)
79+ {
80+ ASSERT_EQ (fts_broadcaster_->on_deactivate (rclcpp_lifecycle::State ()), NODE_SUCCESS);
81+ }
82+ // Clean up the broadcaster
83+ ASSERT_EQ (fts_broadcaster_->on_cleanup (rclcpp_lifecycle::State ()), NODE_SUCCESS);
84+ }
85+ fts_broadcaster_.reset (nullptr );
86+ }
87+ // Add a small delay between tests
88+ std::this_thread::sleep_for (std::chrono::milliseconds (50 ));
89+ }
5590
5691void ForceTorqueSensorBroadcasterTest::SetUpFTSBroadcaster ()
5792{
0 commit comments