You signed in with another tab or window. Reload to refresh your session.You signed out in another tab or window. Reload to refresh your session.You switched accounts on another tab or window. Reload to refresh your session.Dismiss alert
#include<gtest/gtest.h>
#include<memory>
#include"lifecycle_msgs/msg/state.hpp"
#include"rclcpp/rclcpp.hpp"
#include"rclcpp_lifecycle/lifecycle_node.hpp"using std::placeholders::_1;
using lifecycle_msgs::msg::Transition;
using lifecycle_msgs::msg::State;
using CallbackReturn =
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
classTestDefaultStateMachine : public ::testing::Test
{
protected:staticvoidSetUpTestCase()
{
rclcpp::init(0, nullptr);
}
staticvoidTearDownTestCase()
{
rclcpp::shutdown();
}
};
classOnShutdownLifecycleNode : publicrclcpp_lifecycle::LifecycleNode
{
public:explicitOnShutdownLifecycleNode(const std::string & node_name, int & count)
: rclcpp_lifecycle::LifecycleNode(node_name),
on_shutdown_count_(count)
{}
~OnShutdownLifecycleNode() {
RCLCPP_INFO(
get_logger(),
"OnShutdownLifecycleNode::~OnShutdownLifecycleNode | Destroying node!");
}
voidregister_my_shutdown()
{
register_on_shutdown(std::bind(&OnShutdownLifecycleNode::my_shutdown, this, _1));
}
CallbackReturn on_shutdown(const rclcpp_lifecycle::State &)
{
RCLCPP_INFO(get_logger(), "OnShutdownLifecycleNode::on_shutdown called!");
on_shutdown_count_ += 1;
return CallbackReturn::SUCCESS;
}
private:
CallbackReturn my_shutdown(const rclcpp_lifecycle::State & state)
{
RCLCPP_INFO(get_logger(), "OnShutdownLifecycleNode::my_shutdown called!");
on_shutdown_count_ += 1;
returnon_shutdown(state);
}
int & on_shutdown_count_;
};
TEST_F(TestDefaultStateMachine, on_shutdown_not_called_from_dtor)
{
int on_shutdown_count = 0;
auto test_node = std::make_shared<OnShutdownLifecycleNode>(
"testnode", on_shutdown_count);
// `on_shutdown` should be called and the counter should be incremented
test_node.reset();
EXPECT_EQ(on_shutdown_count, 1);
}
TEST_F(TestDefaultStateMachine, my_shutdown_called_but_on_shutdown_not_called_from_dtor)
{
int on_shutdown_count = 0;
auto test_node = std::make_shared<OnShutdownLifecycleNode>(
"testnode", on_shutdown_count);
// Register `my_shutdown` callback that should call `on_shutdown`
test_node->register_my_shutdown();
// The counter should be incremented twice
test_node.reset();
EXPECT_EQ(on_shutdown_count, 2);
}
Expected behavior
Both tests should pass.
Actual behavior
[==========] Running 2 tests from 1 test suite.[----------] Global test environment set-up.[----------] 2 tests from TestDefaultStateMachine[ RUN ] TestDefaultStateMachine.on_shutdown_not_called_from_dtor[INFO] [1717781941.867603435] [testnode]: OnShutdownLifecycleNode::~OnShutdownLifecycleNode | Destroying node!/home/katfish/dev/katfish/src/tools/kraken_roscpp/test/test_node_shutdown_dtor.cpp:134: FailureExpected equality of these values: *on_shutdown_count Which is: 0 1[ FAILED ] TestDefaultStateMachine.on_shutdown_not_called_from_dtor (9 ms)[ RUN ] TestDefaultStateMachine.my_shutdown_called_but_on_shutdown_not_called_from_dtor[INFO] [1717781941.874294214] [testnode]: OnShutdownLifecycleNode::~OnShutdownLifecycleNode | Destroying node![INFO] [1717781941.874322162] [testnode]: OnShutdownLifecycleNode::my_shutdown called!/home/katfish/dev/katfish/src/tools/kraken_roscpp/test/test_node_shutdown_dtor.cpp:148: FailureExpected equality of these values: *on_shutdown_count Which is: 1 2[ FAILED ] TestDefaultStateMachine.my_shutdown_called_but_on_shutdown_not_called_from_dtor (6 ms)[----------] 2 tests from TestDefaultStateMachine (15 ms total)[----------] Global test environment tear-down[==========] 2 tests from 1 test suite ran. (17 ms total)[ PASSED ] 0 tests.[ FAILED ] 2 tests, listed below:[ FAILED ] TestDefaultStateMachine.on_shutdown_not_called_from_dtor[ FAILED ] TestDefaultStateMachine.my_shutdown_called_but_on_shutdown_not_called_from_dtor 2 FAILED TESTS
Additional information
This issue has been found while implementing a local workaround for #2553.
The text was updated successfully, but these errors were encountered:
I believe both tests fail because during object destruction in C++, the derived class dtor is called first, followed by the base class dtor. At this point, the virtual table (vtable) is already updated to reflect the base class, meaning any virtual method calls within the base class destructor will not invoke the overridden methods in the derived class.
Consequently, when rclcpp::LifecycleNode dtor calls shutdown() and triggers the transition, if there is a subclass-defined registration of a non-virtual method (although it can lead to undesired behavior as shown in #2553) the appropriate derived class method is called while any call to a virtual method (such as on_shutdown) will call the base class implementation.
Bug report
Required Info:
Steps to reproduce issue
Execute the following test suite:
Expected behavior
Both tests should pass.
Actual behavior
Additional information
This issue has been found while implementing a local workaround for #2553.
The text was updated successfully, but these errors were encountered: