Skip to content

Commit 304b51c

Browse files
clalancetteahcorde
andauthored
Fix the lifecycle tests on RHEL-9. (#2583)
* Fix the lifecycle tests on RHEL-9. The full explanation is in the comment, but basically since RHEL doesn't support mocking_utils::inject_on_return, we have to split out certain tests to make sure resources within a process don't collide. Signed-off-by: Chris Lalancette <clalancette@gmail.com> Co-authored-by: Alejandro Hernández Cordero <ahcorde@gmail.com>
1 parent 069a001 commit 304b51c

File tree

3 files changed

+76
-16
lines changed

3 files changed

+76
-16
lines changed

rclcpp_lifecycle/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -99,6 +99,13 @@ if(BUILD_TESTING)
9999
if(TARGET test_lifecycle_node)
100100
target_link_libraries(test_lifecycle_node ${PROJECT_NAME} mimick rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp rcutils::rcutils)
101101
endif()
102+
103+
ament_add_gtest(test_lifecycle_node_errors test/test_lifecycle_node_errors.cpp)
104+
ament_add_test_label(test_lifecycle_node_errors mimick)
105+
if(TARGET test_lifecycle_node_errors)
106+
target_link_libraries(test_lifecycle_node_errors ${PROJECT_NAME} mimick rcl_lifecycle::rcl_lifecycle)
107+
endif()
108+
102109
ament_add_gtest(test_lifecycle_publisher test/test_lifecycle_publisher.cpp)
103110
if(TARGET test_lifecycle_publisher)
104111
target_link_libraries(test_lifecycle_publisher ${PROJECT_NAME} rcl_lifecycle::rcl_lifecycle rclcpp::rclcpp ${test_msgs_TARGETS})

rclcpp_lifecycle/test/test_lifecycle_node.cpp

Lines changed: 0 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -237,22 +237,6 @@ TEST_F(TestDefaultStateMachine, empty_initializer) {
237237
EXPECT_EQ(State::PRIMARY_STATE_UNCONFIGURED, test_node->get_current_state().id());
238238
}
239239

240-
TEST_F(TestDefaultStateMachine, empty_initializer_rcl_errors) {
241-
{
242-
auto patch = mocking_utils::inject_on_return(
243-
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_init, RCL_RET_ERROR);
244-
EXPECT_THROW(
245-
std::make_shared<EmptyLifecycleNode>("testnode").reset(),
246-
std::runtime_error);
247-
}
248-
{
249-
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
250-
auto patch = mocking_utils::inject_on_return(
251-
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_fini, RCL_RET_ERROR);
252-
EXPECT_NO_THROW(test_node.reset());
253-
}
254-
}
255-
256240
TEST_F(TestDefaultStateMachine, check_logger_services_exist) {
257241
// Logger level services are disabled
258242
{
Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
// Copyright 2024 Open Source Robotics Foundation, Inc.
2+
//
3+
// Licensed under the Apache License, Version 2.0 (the "License");
4+
// you may not use this file except in compliance with the License.
5+
// You may obtain a copy of the License at
6+
//
7+
// http://www.apache.org/licenses/LICENSE-2.0
8+
//
9+
// Unless required by applicable law or agreed to in writing, software
10+
// distributed under the License is distributed on an "AS IS" BASIS,
11+
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12+
// See the License for the specific language governing permissions and
13+
// limitations under the License.
14+
15+
#include <gtest/gtest.h>
16+
17+
#include <memory>
18+
#include <stdexcept>
19+
#include <string>
20+
21+
#include "rcl_lifecycle/rcl_lifecycle.h"
22+
23+
#include "rclcpp_lifecycle/lifecycle_node.hpp"
24+
25+
#include "./mocking_utils/patch.hpp"
26+
27+
class TestDefaultStateMachine : public ::testing::Test
28+
{
29+
protected:
30+
static void SetUpTestCase()
31+
{
32+
rclcpp::init(0, nullptr);
33+
}
34+
static void TearDownTestCase()
35+
{
36+
rclcpp::shutdown();
37+
}
38+
};
39+
40+
class EmptyLifecycleNode : public rclcpp_lifecycle::LifecycleNode
41+
{
42+
public:
43+
explicit EmptyLifecycleNode(const std::string & node_name)
44+
: rclcpp_lifecycle::LifecycleNode(node_name)
45+
{}
46+
};
47+
48+
// This test is split out of test_lifecycle_node.cpp for an esoteric reason. When running on
49+
// RedHat-based distributions (like Fedora or RHEL), the way that glibc is compiled does not
50+
// allow mocking_utils::inject_on_return to work. Thus the test has to patch_and_return().
51+
// Unfortunately, this means that the resources are not actually cleaned up, and thus other tests
52+
// may return incorrect results. By having it in a separate process we ensure that the resources
53+
// will at least be cleaned up by the process dying.
54+
TEST_F(TestDefaultStateMachine, empty_initializer_rcl_errors)
55+
{
56+
{
57+
auto patch = mocking_utils::patch_and_return(
58+
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_init, RCL_RET_ERROR);
59+
EXPECT_THROW(
60+
std::make_shared<EmptyLifecycleNode>("testnode").reset(),
61+
std::runtime_error);
62+
}
63+
{
64+
auto test_node = std::make_shared<EmptyLifecycleNode>("testnode");
65+
auto patch = mocking_utils::patch_and_return(
66+
"lib:rclcpp_lifecycle", rcl_lifecycle_state_machine_fini, RCL_RET_ERROR);
67+
EXPECT_NO_THROW(test_node.reset());
68+
}
69+
}

0 commit comments

Comments
 (0)