Skip to content

Commit 28c7bb2

Browse files
committed
Gracefully handle CTRL+C and CTR+Break events on Windows
- Add handler for the native Windows CTRL_C_EVENT, CTRL_BREAK_EVENT and CTRL_CLOSE_EVENT in rosbag2 recorder and player. - Map SIGINT signal to the native Windows CTRL_C_EVENT in the stop_execution(handle, signum) version for Windows. To be able correctly use start and stop execution routines from unit tests. - Enable integration tests which was disabled for Windows due to the incorrect sending and handling of the SIGINT event. - Got rid of the `finalize_metadata_kludge(..)` helper function. Signed-off-by: Michael <[email protected]>
1 parent 1f2c53a commit 28c7bb2

File tree

6 files changed

+129
-79
lines changed

6 files changed

+129
-79
lines changed

rosbag2_py/src/rosbag2_py/_transport.cpp

+84-4
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,11 @@
3131

3232
#include "./pybind11.hpp"
3333

34+
#ifdef _WIN32
35+
#include <windows.h>
36+
#include <iostream>
37+
#endif
38+
3439
namespace py = pybind11;
3540
typedef std::unordered_map<std::string, rclcpp::QoS> QoSMap;
3641

@@ -132,7 +137,49 @@ class Player
132137
public:
133138
Player()
134139
{
135-
rclcpp::init(0, nullptr);
140+
auto init_options = rclcpp::InitOptions();
141+
init_options.shutdown_on_signal = false;
142+
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::None);
143+
std::signal(
144+
SIGTERM, [](int /* signal */) {
145+
rclcpp::shutdown();
146+
});
147+
std::signal(
148+
SIGINT, [](int /* signal */) {
149+
rclcpp::shutdown();
150+
});
151+
#ifdef _WIN32
152+
// According to the
153+
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
154+
// SIGINT is not supported for any Win32 application. When a CTRL+C interrupt occurs,
155+
// Win32 operating systems generate a new thread to specifically handle that interrupt.
156+
// Therefore, need to use native Windows control event handler as analog for the SIGINT.
157+
158+
// Enable default CTRL+C handler first. This is workaround and needed for the cases when
159+
// process created with CREATE_NEW_PROCESS_GROUP flag. Without it, installing custom Ctrl+C
160+
// handler will not work.
161+
if (!SetConsoleCtrlHandler(nullptr, false)) {
162+
std::cerr << "Rosbag2 player error: Failed to enable default CTL+C handler.\n";
163+
}
164+
// Installing our own control handler
165+
auto CtrlHandler = [](DWORD fdwCtrlType) -> BOOL {
166+
switch (fdwCtrlType) {
167+
case CTRL_C_EVENT:
168+
case CTRL_BREAK_EVENT:
169+
case CTRL_CLOSE_EVENT:
170+
rclcpp::shutdown();
171+
return TRUE;
172+
case CTRL_SHUTDOWN_EVENT:
173+
rclcpp::shutdown();
174+
return FALSE;
175+
default:
176+
return FALSE;
177+
}
178+
};
179+
if (!SetConsoleCtrlHandler(CtrlHandler, TRUE)) {
180+
std::cerr << "Rosbag2 player error: Could not set control handler.\n";
181+
}
182+
#endif // #ifdef _WIN32
136183
}
137184

138185
virtual ~Player()
@@ -157,7 +204,7 @@ class Player
157204
player->play();
158205

159206
exec.cancel();
160-
spin_thread.join();
207+
if (spin_thread.joinable()) {spin_thread.join();}
161208
}
162209

163210
void burst(
@@ -182,8 +229,8 @@ class Player
182229
player->burst(num_messages);
183230

184231
exec.cancel();
185-
spin_thread.join();
186-
play_thread.join();
232+
if (spin_thread.joinable()) {spin_thread.join();}
233+
if (play_thread.joinable()) {play_thread.join();}
187234
}
188235
};
189236

@@ -208,6 +255,39 @@ class Recorder
208255
SIGINT, [](int /* signal */) {
209256
rosbag2_py::Recorder::cancel();
210257
});
258+
#ifdef _WIN32
259+
// According to the
260+
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
261+
// SIGINT is not supported for any Win32 application. When a CTRL+C interrupt occurs,
262+
// Win32 operating systems generate a new thread to specifically handle that interrupt.
263+
// Therefore, need to use native Windows control event handler as analog for the SIGINT.
264+
265+
// Enable default CTRL+C handler first. This is workaround and needed for the cases when
266+
// process created with CREATE_NEW_PROCESS_GROUP flag. Without it, installing custom Ctrl+C
267+
// handler will not work.
268+
if (!SetConsoleCtrlHandler(nullptr, false)) {
269+
std::cerr << "Rosbag2 recorder error: Failed to enable default CTL+C handler.\n";
270+
}
271+
// Installing our own control handler
272+
auto CtrlHandler = [](DWORD fdwCtrlType) -> BOOL {
273+
switch (fdwCtrlType) {
274+
case CTRL_C_EVENT:
275+
case CTRL_BREAK_EVENT:
276+
case CTRL_CLOSE_EVENT:
277+
rosbag2_py::Recorder::cancel();
278+
return TRUE;
279+
case CTRL_SHUTDOWN_EVENT:
280+
rosbag2_py::Recorder::cancel();
281+
rclcpp::shutdown();
282+
return FALSE;
283+
default:
284+
return FALSE;
285+
}
286+
};
287+
if (!SetConsoleCtrlHandler(CtrlHandler, TRUE)) {
288+
std::cerr << "Rosbag2 recorder error: Could not set control handler.\n";
289+
}
290+
#endif // #ifdef _WIN32
211291
}
212292

213293
virtual ~Recorder()

rosbag2_test_common/include/rosbag2_test_common/process_execution_helpers_windows.hpp

+40-14
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@
1818
#include <gmock/gmock.h>
1919

2020
#include <direct.h>
21-
#include <Windows.h>
21+
#include <windows.h>
2222

2323
#include <chrono>
2424
#include <csignal>
@@ -46,7 +46,10 @@ PROCESS_INFORMATION create_process(TCHAR * command, const char * path = nullptr)
4646
nullptr,
4747
nullptr,
4848
false,
49-
0,
49+
// Create process suspended and resume it after adding to the newly created job. Otherwise,
50+
// there is a potential race condition where newly created process starts a subprocess
51+
// before we've called AssignProcessToJobObject();
52+
CREATE_NEW_PROCESS_GROUP | CREATE_SUSPENDED,
5053
nullptr,
5154
path,
5255
&start_up_info,
@@ -73,8 +76,9 @@ int execute_and_wait_until_completion(const std::string & command, const std::st
7376
const_char_to_tchar(command.c_str(), command_char);
7477

7578
auto process = create_process(command_char, path.c_str());
76-
DWORD exit_code = 259; // 259 is the code one gets if the process is still active.
77-
while (exit_code == 259) {
79+
ResumeThread(process.hThread);
80+
DWORD exit_code = STILL_ACTIVE;
81+
while (exit_code == STILL_ACTIVE) {
7882
EXPECT_TRUE(GetExitCodeProcess(process.hProcess, &exit_code));
7983
std::this_thread::sleep_for(std::chrono::milliseconds(10));
8084
}
@@ -97,6 +101,7 @@ ProcessHandle start_execution(const std::string & command)
97101
auto process_info = create_process(command_char);
98102

99103
AssignProcessToJobObject(h_job, process_info.hProcess);
104+
ResumeThread(process_info.hThread);
100105
Process process;
101106
process.process_info = process_info;
102107
process.job_handle = h_job;
@@ -117,12 +122,12 @@ bool wait_until_completion(
117122
DWORD exit_code = 0;
118123
std::chrono::steady_clock::time_point const start = std::chrono::steady_clock::now();
119124
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
120-
// 259 indicates that the process is still active
121-
while (exit_code == 259 && std::chrono::steady_clock::now() - start < timeout) {
125+
while (exit_code == STILL_ACTIVE && std::chrono::steady_clock::now() - start < timeout) {
122126
std::this_thread::sleep_for(std::chrono::milliseconds(10));
123127
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
124128
}
125-
return exit_code != 259;
129+
EXPECT_EQ(exit_code, 0);
130+
return exit_code != STILL_ACTIVE;
126131
}
127132

128133
/// @brief Force to stop process with signal if it's currently running
@@ -135,16 +140,37 @@ void stop_execution(
135140
std::chrono::duration<double> timeout = std::chrono::seconds(10))
136141
{
137142
// Match the Unix version by allowing for int signum argument - however Windows does not have
138-
// Linux signals in the same way, so there isn't a 1:1 mapping to dispatch e.g. SIGTERM
139-
DWORD exit_code;
143+
// Linux signals in the same way, so there isn't a 1:1 mapping to dispatch e.g. SIGINT or SIGTERM
144+
DWORD exit_code = STILL_ACTIVE;
140145
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
141-
// 259 indicates that the process is still active: we want to make sure that the process is
142-
// still running properly before killing it.
143-
if (exit_code == 259) {
144-
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_C_EVENT, handle.process_info.dwThreadId));
146+
// Make sure that the process is still running properly before stopping it.
147+
if (exit_code == STILL_ACTIVE) {
148+
switch (signum) {
149+
// According to the
150+
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
151+
// SIGINT and SIGBREAK is not supported for any Win32 application.
152+
// Need to use native Windows control event instead.
153+
case SIGINT:
154+
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_C_EVENT, handle.process_info.dwProcessId));
155+
break;
156+
case SIGBREAK:
157+
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_BREAK_EVENT, handle.process_info.dwProcessId));
158+
break;
159+
case SIGTERM:
160+
// The CTRL_CLOSE_EVENT is analog of the SIGTERM from POSIX. Windows sends CTRL_CLOSE_EVENT
161+
// to all processes attached to a console when the user closes the console (either by
162+
// clicking Close on the console window's window menu, or by clicking the End Task
163+
// button command from Task Manager). Although according to the
164+
// https://learn.microsoft.com/en-us/windows/console/generateconsolectrlevent the
165+
// GenerateConsoleCtrlEvent doesn't support sending CTRL_CLOSE_EVENT. There are no way to
166+
// directly send CTRL_CLOSE_EVENT to the process in the same console application.
167+
// Therefore, adding SIGTERM to the unsupported events.
168+
default:
169+
throw std::runtime_error("Unsupported signum: " + std::to_string(signum));
170+
}
145171
bool process_finished = wait_until_completion(handle, timeout);
146172
if (!process_finished) {
147-
std::cerr << "Testing process " << handle.process_info.hProcess <<
173+
std::cerr << "Testing process " << handle.process_info.dwProcessId <<
148174
" hangout. Killing it with TerminateProcess(..) \n";
149175
EXPECT_TRUE(TerminateProcess(handle.process_info.hProcess, 2));
150176
EXPECT_TRUE(process_finished);

rosbag2_tests/test/rosbag2_tests/record_fixture.hpp

+1-39
Original file line numberDiff line numberDiff line change
@@ -126,7 +126,7 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture
126126
std::this_thread::sleep_for(50ms);
127127
}
128128
ASSERT_EQ(metadata_io.metadata_file_exists(bag_path), true)
129-
<< "Could not find metadata file.";
129+
<< "Could not find " << bag_path << " metadata file.";
130130
}
131131

132132
void wait_for_storage_file(std::chrono::duration<float> timeout = std::chrono::seconds(10))
@@ -181,44 +181,6 @@ class RecordFixture : public ParametrizedTemporaryDirectoryFixture
181181
return topic_it->serialization_format;
182182
}
183183

184-
void finalize_metadata_kludge(
185-
int expected_splits = 0,
186-
const std::string & compression_format = "",
187-
const std::string & compression_mode = "")
188-
{
189-
// TODO(ros-tooling): Find out how to correctly send a Ctrl-C signal on Windows
190-
// This is necessary as the process is killed hard on Windows and doesn't write a metadata file
191-
#ifdef _WIN32
192-
rosbag2_storage::BagMetadata metadata{};
193-
metadata.storage_identifier = rosbag2_storage::get_default_storage_id();
194-
for (int i = 0; i <= expected_splits; i++) {
195-
rcpputils::fs::path bag_file_path;
196-
if (!compression_format.empty()) {
197-
bag_file_path = get_bag_file_path(i);
198-
} else {
199-
bag_file_path = get_compressed_bag_file_path(i);
200-
}
201-
202-
if (rcpputils::fs::exists(bag_file_path)) {
203-
metadata.relative_file_paths.push_back(bag_file_path.string());
204-
}
205-
}
206-
metadata.duration = std::chrono::nanoseconds(0);
207-
metadata.starting_time =
208-
std::chrono::time_point<std::chrono::high_resolution_clock>(std::chrono::nanoseconds(0));
209-
metadata.message_count = 0;
210-
metadata.compression_mode = compression_mode;
211-
metadata.compression_format = compression_format;
212-
213-
rosbag2_storage::MetadataIo metadata_io;
214-
metadata_io.write_metadata(root_bag_path_.string(), metadata);
215-
#else
216-
(void)expected_splits;
217-
(void)compression_format;
218-
(void)compression_mode;
219-
#endif
220-
}
221-
222184
// relative path to the root of the bag file.
223185
rcpputils::fs::path root_bag_path_;
224186

rosbag2_tests/test/rosbag2_tests/test_rosbag2_play_end_to_end.cpp

-2
Original file line numberDiff line numberDiff line change
@@ -271,7 +271,6 @@ TEST_P(PlayEndToEndTestFixture, play_filters_by_topic) {
271271
}
272272
}
273273

274-
#ifndef _WIN32
275274
TEST_P(PlayEndToEndTestFixture, play_end_to_end_exits_gracefully_on_sigint) {
276275
sub_->add_subscription<test_msgs::msg::BasicTypes>("/test_topic", 3, sub_qos_);
277276
sub_->add_subscription<test_msgs::msg::Arrays>("/array_topic", 2, sub_qos_);
@@ -293,7 +292,6 @@ TEST_P(PlayEndToEndTestFixture, play_end_to_end_exits_gracefully_on_sigint) {
293292
stop_execution(process_id, SIGINT);
294293
cleanup_process_handle.cancel();
295294
}
296-
#endif // #ifndef _WIN32
297295

298296
INSTANTIATE_TEST_SUITE_P(
299297
TestPlayEndToEnd,

0 commit comments

Comments
 (0)