Skip to content

Commit dfeb3d1

Browse files
Allow tracing tests to be run in parallel with other tests (#95)
* Only consider relevant test trace data in tracing tests * Allow having existing tracing sessions during tracing tests But make sure the tests do not leave tracing sessions behind. Signed-off-by: Christophe Bedard <[email protected]>
1 parent 975bf6a commit dfeb3d1

20 files changed

+410
-73
lines changed

test_ros2trace/package.xml

+1
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
<test_depend>test_tracetools</test_depend>
2626
<test_depend>tracetools</test_depend>
2727
<test_depend>tracetools_read</test_depend>
28+
<test_depend>tracetools_test</test_depend>
2829
<test_depend>tracetools_trace</test_depend>
2930

3031
<!-- TODO(clalancette): This is actually a false dependency,

test_ros2trace/test/test_ros2trace/test_trace.py

+114-59
Large diffs are not rendered by default.

test_tracetools/CMakeLists.txt

+31
Original file line numberDiff line numberDiff line change
@@ -36,13 +36,36 @@ if(BUILD_TESTING)
3636
find_package(lifecycle_msgs REQUIRED)
3737
find_package(rclcpp REQUIRED)
3838
find_package(rclcpp_lifecycle REQUIRED)
39+
find_package(rcpputils REQUIRED)
3940
find_package(std_msgs REQUIRED)
4041
find_package(std_srvs REQUIRED)
4142

43+
# The utility lib is needed even if TRACETOOLS_DISABLED; it's just empty
44+
add_library(${PROJECT_NAME}_mark_process src/mark_process.cpp)
45+
if(NOT TRACETOOLS_DISABLED)
46+
find_package(PkgConfig REQUIRED)
47+
pkg_check_modules(LTTNG REQUIRED lttng-ust)
48+
target_link_libraries(${PROJECT_NAME}_mark_process PRIVATE
49+
${LTTNG_LIBRARIES}
50+
rcpputils::rcpputils
51+
)
52+
endif()
53+
target_include_directories(${PROJECT_NAME}_mark_process PUBLIC
54+
"$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>"
55+
)
56+
if(TRACETOOLS_DISABLED)
57+
target_compile_definitions(${PROJECT_NAME}_mark_process PRIVATE TRACETOOLS_DISABLED)
58+
endif()
59+
install(
60+
DIRECTORY include/
61+
DESTINATION include/${PROJECT_NAME}
62+
)
63+
4264
add_executable(test_publisher
4365
src/test_publisher.cpp
4466
)
4567
target_link_libraries(test_publisher PRIVATE
68+
${PROJECT_NAME}_mark_process
4669
rclcpp::rclcpp
4770
${std_msgs_TARGETS}
4871
)
@@ -51,6 +74,7 @@ if(BUILD_TESTING)
5174
src/test_intra.cpp
5275
)
5376
target_link_libraries(test_intra PRIVATE
77+
${PROJECT_NAME}_mark_process
5478
rclcpp::rclcpp
5579
${std_msgs_TARGETS}
5680
)
@@ -59,6 +83,7 @@ if(BUILD_TESTING)
5983
src/test_lifecycle_node.cpp
6084
)
6185
target_link_libraries(test_lifecycle_node PRIVATE
86+
${PROJECT_NAME}_mark_process
6287
rclcpp::rclcpp
6388
rclcpp_lifecycle::rclcpp_lifecycle
6489
)
@@ -67,6 +92,7 @@ if(BUILD_TESTING)
6792
src/test_lifecycle_client.cpp
6893
)
6994
target_link_libraries(test_lifecycle_client PRIVATE
95+
${PROJECT_NAME}_mark_process
7096
${lifecycle_msgs_TARGETS}
7197
rclcpp::rclcpp
7298
)
@@ -75,6 +101,7 @@ if(BUILD_TESTING)
75101
src/test_ping.cpp
76102
)
77103
target_link_libraries(test_ping PRIVATE
104+
${PROJECT_NAME}_mark_process
78105
rclcpp::rclcpp
79106
${std_msgs_TARGETS}
80107
)
@@ -83,6 +110,7 @@ if(BUILD_TESTING)
83110
src/test_pong.cpp
84111
)
85112
target_link_libraries(test_pong PRIVATE
113+
${PROJECT_NAME}_mark_process
86114
rclcpp::rclcpp
87115
${std_msgs_TARGETS}
88116
)
@@ -91,13 +119,15 @@ if(BUILD_TESTING)
91119
src/test_timer.cpp
92120
)
93121
target_link_libraries(test_timer PRIVATE
122+
${PROJECT_NAME}_mark_process
94123
rclcpp::rclcpp
95124
)
96125

97126
add_executable(test_service_ping
98127
src/test_service_ping.cpp
99128
)
100129
target_link_libraries(test_service_ping PRIVATE
130+
${PROJECT_NAME}_mark_process
101131
rclcpp::rclcpp
102132
${std_srvs_TARGETS}
103133
)
@@ -106,6 +136,7 @@ if(BUILD_TESTING)
106136
src/test_service_pong.cpp
107137
)
108138
target_link_libraries(test_service_pong PRIVATE
139+
${PROJECT_NAME}_mark_process
109140
rclcpp::rclcpp
110141
${std_srvs_TARGETS}
111142
)
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,41 @@
1+
// Copyright 2024 Apex.AI, 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+
#ifndef TEST_TRACETOOLS__MARK_PROCESS_HPP_
16+
#define TEST_TRACETOOLS__MARK_PROCESS_HPP_
17+
18+
#include <string>
19+
20+
namespace test_tracetools
21+
{
22+
23+
/// Mark process to link it to a trace test.
24+
/**
25+
* This should be called once by each test application (process) to mark the process so that it can
26+
* be linked to the trace test that spawned it.
27+
*
28+
* The process responsible for spawning the current process is responsible for setting the
29+
* `TRACETOOLS_TEST_TRACE_TEST_ID` environment variable to a unique value.
30+
*
31+
* If the `TRACETOOLS_TEST_TRACE_TEST_ID` environment variable is set and not empty, this marks the
32+
* current process by triggering an `lttng_ust_tracef:event` trace event with a `msg` field value
33+
* equal to: `"TRACETOOLS_TEST_TRACE_TEST_ID=<value of TRACETOOLS_TEST_TRACE_TEST_ID>"`.
34+
*
35+
* \see tracetools_test
36+
*/
37+
void mark_trace_test_process();
38+
39+
} // namespace test_tracetools
40+
41+
#endif // TEST_TRACETOOLS__MARK_PROCESS_HPP_

test_tracetools/package.xml

+4
Original file line numberDiff line numberDiff line change
@@ -20,9 +20,11 @@
2020
the dependencies that those packages use so that colcon properly sets up the
2121
environment when running those tests.
2222
-->
23+
<build_export_depend>liblttng-ust-dev</build_export_depend>
2324
<build_export_depend>lifecycle_msgs</build_export_depend>
2425
<build_export_depend>rclcpp</build_export_depend>
2526
<build_export_depend>rclcpp_lifecycle</build_export_depend>
27+
<build_export_depend>rcpputils</build_export_depend>
2628
<build_export_depend>std_msgs</build_export_depend>
2729
<build_export_depend>std_srvs</build_export_depend>
2830

@@ -31,11 +33,13 @@
3133
<test_depend>ament_cmake_pytest</test_depend>
3234
<test_depend>ament_lint_auto</test_depend>
3335
<test_depend>ament_lint_common</test_depend>
36+
<test_depend>liblttng-ust-dev</test_depend>
3437
<test_depend>lifecycle_msgs</test_depend>
3538
<test_depend>python3-pytest</test_depend>
3639
<test_depend>python3-pytest-cov</test_depend>
3740
<test_depend>rclcpp</test_depend>
3841
<test_depend>rclcpp_lifecycle</test_depend>
42+
<test_depend>rcpputils</test_depend>
3943
<test_depend>std_msgs</test_depend>
4044
<test_depend>std_srvs</test_depend>
4145
<test_depend>tracetools</test_depend>

test_tracetools/src/mark_process.cpp

+48
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
// Copyright 2024 Apex.AI, 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+
#ifndef TRACETOOLS_DISABLED
16+
#include <lttng/tracef.h>
17+
18+
#include "rcpputils/env.hpp"
19+
#endif // TRACETOOLS_DISABLED
20+
21+
#include "test_tracetools/mark_process.hpp"
22+
23+
namespace test_tracetools
24+
{
25+
26+
namespace
27+
{
28+
29+
/**
30+
* \see tracetools_test
31+
*/
32+
constexpr std::string_view trace_test_id_env_var = "TRACETOOLS_TEST_TRACE_TEST_ID";
33+
34+
} // namespace
35+
36+
void mark_trace_test_process()
37+
{
38+
#ifndef TRACETOOLS_DISABLED
39+
// See tracetools_test.mark_process for more details
40+
const std::string env_var{trace_test_id_env_var};
41+
const auto test_id = rcpputils::get_env_var(env_var.c_str());
42+
if (!test_id.empty()) {
43+
lttng_ust__tracef("%s=%s", env_var.c_str(), test_id.c_str());
44+
}
45+
#endif // TRACETOOLS_DISABLED
46+
}
47+
48+
} // namespace test_tracetools

test_tracetools/src/test_intra.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "rclcpp/rclcpp.hpp"
1818
#include "std_msgs/msg/string.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
using namespace std::chrono_literals;
2122

@@ -73,6 +74,8 @@ class SubIntraNode : public rclcpp::Node
7374

7475
int main(int argc, char * argv[])
7576
{
77+
test_tracetools::mark_trace_test_process();
78+
7679
rclcpp::init(argc, argv);
7780

7881
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_lifecycle_client.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -25,6 +25,7 @@
2525
#include "lifecycle_msgs/srv/get_state.hpp"
2626
#include "rclcpp/rclcpp.hpp"
2727
#include "rcutils/logging_macros.h"
28+
#include "test_tracetools/mark_process.hpp"
2829

2930
using namespace std::chrono_literals;
3031

@@ -256,6 +257,8 @@ void cycle_through_states(std::shared_ptr<LifecycleNodeClient> client_node)
256257

257258
int main(int argc, char ** argv)
258259
{
260+
test_tracetools::mark_trace_test_process();
261+
259262
rclcpp::init(argc, argv);
260263

261264
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_lifecycle_node.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "rclcpp/rclcpp.hpp"
1818
#include "rclcpp_lifecycle/lifecycle_node.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
2122
{
@@ -66,6 +67,8 @@ class LifecycleNode : public rclcpp_lifecycle::LifecycleNode
6667

6768
int main(int argc, char ** argv)
6869
{
70+
test_tracetools::mark_trace_test_process();
71+
6972
rclcpp::init(argc, argv);
7073

7174
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_ping.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "rclcpp/rclcpp.hpp"
1919
#include "std_msgs/msg/string.hpp"
20+
#include "test_tracetools/mark_process.hpp"
2021

2122
using namespace std::chrono_literals;
2223

@@ -70,6 +71,8 @@ class PingNode : public rclcpp::Node
7071

7172
int main(int argc, char * argv[])
7273
{
74+
test_tracetools::mark_trace_test_process();
75+
7376
bool do_only_one = true;
7477
for (int i = 0; i < argc; ++i) {
7578
if (strncmp(argv[i], "do_more", 7) == 0) {

test_tracetools/src/test_pong.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "rclcpp/rclcpp.hpp"
1818
#include "std_msgs/msg/string.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
#define NODE_NAME "test_pong"
2122
#define SUB_TOPIC_NAME "ping"
@@ -58,6 +59,8 @@ class PongNode : public rclcpp::Node
5859

5960
int main(int argc, char * argv[])
6061
{
62+
test_tracetools::mark_trace_test_process();
63+
6164
bool do_only_one = true;
6265
for (int i = 0; i < argc; ++i) {
6366
if (strncmp(argv[i], "do_more", 7) == 0) {

test_tracetools/src/test_publisher.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "rclcpp/rclcpp.hpp"
1919
#include "std_msgs/msg/string.hpp"
20+
#include "test_tracetools/mark_process.hpp"
2021

2122
#define NODE_NAME "test_publisher"
2223
#define TOPIC_NAME "the_topic"
@@ -43,6 +44,8 @@ class PubNode : public rclcpp::Node
4344

4445
int main(int argc, char * argv[])
4546
{
47+
test_tracetools::mark_trace_test_process();
48+
4649
rclcpp::init(argc, argv);
4750

4851
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_service.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "rclcpp/rclcpp.hpp"
1818
#include "std_srvs/srv/empty.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
#define NODE_NAME "test_service"
2122
#define SERVICE_NAME "the_service"
@@ -53,6 +54,8 @@ class ServiceNode : public rclcpp::Node
5354

5455
int main(int argc, char * argv[])
5556
{
57+
test_tracetools::mark_trace_test_process();
58+
5659
rclcpp::init(argc, argv);
5760

5861
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_service_ping.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -17,6 +17,7 @@
1717

1818
#include "rclcpp/rclcpp.hpp"
1919
#include "std_srvs/srv/empty.hpp"
20+
#include "test_tracetools/mark_process.hpp"
2021

2122
using namespace std::chrono_literals;
2223

@@ -71,6 +72,8 @@ class PingNode : public rclcpp::Node
7172

7273
int main(int argc, char * argv[])
7374
{
75+
test_tracetools::mark_trace_test_process();
76+
7477
rclcpp::init(argc, argv);
7578

7679
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_service_pong.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616

1717
#include "rclcpp/rclcpp.hpp"
1818
#include "std_srvs/srv/empty.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
#define NODE_NAME "test_service_pong"
2122
#define SERVICE_NAME "ping"
@@ -59,6 +60,8 @@ class PongNode : public rclcpp::Node
5960

6061
int main(int argc, char * argv[])
6162
{
63+
test_tracetools::mark_trace_test_process();
64+
6265
rclcpp::init(argc, argv);
6366

6467
rclcpp::executors::SingleThreadedExecutor exec;

test_tracetools/src/test_timer.cpp

+3
Original file line numberDiff line numberDiff line change
@@ -16,6 +16,7 @@
1616
#include <chrono>
1717

1818
#include "rclcpp/rclcpp.hpp"
19+
#include "test_tracetools/mark_process.hpp"
1920

2021
using namespace std::chrono_literals;
2122

@@ -50,6 +51,8 @@ class TimerNode : public rclcpp::Node
5051

5152
int main(int argc, char * argv[])
5253
{
54+
test_tracetools::mark_trace_test_process();
55+
5356
rclcpp::init(argc, argv);
5457

5558
rclcpp::executors::SingleThreadedExecutor exec;

0 commit comments

Comments
 (0)