Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Gracefully handle CTRL+C and CTR+Break events on Windows #1342

Open
wants to merge 4 commits into
base: rolling
Choose a base branch
from
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 2 additions & 5 deletions ros2bag/test/test_record.py
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,10 @@ class TestRecord(unittest.TestCase):

def test_output(self, record_all_process, proc_output):
proc_output.assertWaitFor(
'Listening for topics...',
process=record_all_process
)
proc_output.assertWaitFor(
"Subscribed to topic '/rosout'",
"Subscribed to topic '/events/write_split'",
process=record_all_process
)
proc_output.assertWaitFor('Recording...', process=record_all_process)


@launch_testing.post_shutdown_test()
Expand Down
4 changes: 2 additions & 2 deletions ros2bag/test/test_record_qos_profiles.py
Original file line number Diff line number Diff line change
Expand Up @@ -84,7 +84,7 @@ def test_qos_simple(self):
output_path = Path(self.tmpdir.name) / 'ros2bag_test_basic'
arguments = ['record', '-a', '--qos-profile-overrides-path', profile_path.as_posix(),
'--output', output_path.as_posix()]
expected_output = 'Listening for topics...'
expected_output = 'Recording...'
with self.launch_bag_command(arguments=arguments) as bag_command:
bag_command.wait_for_output(
condition=lambda output: expected_output in output,
Expand All @@ -99,7 +99,7 @@ def test_incomplete_qos_profile(self):
output_path = Path(self.tmpdir.name) / 'ros2bag_test_incomplete'
arguments = ['record', '-a', '--qos-profile-overrides-path', profile_path.as_posix(),
'--output', output_path.as_posix()]
expected_output = 'Listening for topics...'
expected_output = 'Recording...'
with self.launch_bag_command(arguments=arguments) as bag_command:
bag_command.wait_for_output(
condition=lambda output: expected_output in output,
Expand Down
101 changes: 98 additions & 3 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,11 @@

#include "./pybind11.hpp"

#ifdef _WIN32
#include <windows.h>
#include <iostream>
#endif

namespace py = pybind11;
typedef std::unordered_map<std::string, rclcpp::QoS> QoSMap;

Expand Down Expand Up @@ -132,7 +137,49 @@ class Player
public:
Player()
{
rclcpp::init(0, nullptr);
auto init_options = rclcpp::InitOptions();
init_options.shutdown_on_signal = false;
rclcpp::init(0, nullptr, init_options, rclcpp::SignalHandlerOptions::None);
std::signal(
SIGTERM, [](int /* signal */) {
rclcpp::shutdown();
});
std::signal(
SIGINT, [](int /* signal */) {
rclcpp::shutdown();
});
#ifdef _WIN32
// According to the
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
// SIGINT is not supported for any Win32 application. When a CTRL+C interrupt occurs,
// Win32 operating systems generate a new thread to specifically handle that interrupt.
// Therefore, need to use native Windows control event handler as analog for the SIGINT.

// Enable default CTRL+C handler first. This is workaround and needed for the cases when
// process created with CREATE_NEW_PROCESS_GROUP flag. Without it, installing custom Ctrl+C
// handler will not work.
if (!SetConsoleCtrlHandler(nullptr, false)) {
std::cerr << "Rosbag2 player error: Failed to enable default CTL+C handler. \n";
}
// Installing our own control handler
auto CtrlHandler = [](DWORD fdwCtrlType) -> BOOL {
switch (fdwCtrlType) {
case CTRL_C_EVENT:
case CTRL_BREAK_EVENT:
case CTRL_CLOSE_EVENT:
rclcpp::shutdown();
return TRUE;
case CTRL_SHUTDOWN_EVENT:
rclcpp::shutdown();
return FALSE;
default:
return FALSE;
}
};
if (!SetConsoleCtrlHandler(CtrlHandler, TRUE)) {
std::cerr << "Rosbag2 player error: Could not set control handler.\n";
}
#endif // #ifdef _WIN32
}

virtual ~Player()
Expand All @@ -158,7 +205,7 @@ class Player
player->wait_for_playback_to_finish();

exec.cancel();
spin_thread.join();
if (spin_thread.joinable()) {spin_thread.join();}
}

void burst(
Expand All @@ -180,7 +227,8 @@ class Player
player->burst(num_messages);

exec.cancel();
spin_thread.join();
if (spin_thread.joinable()) {spin_thread.join();}
if (play_thread.joinable()) {play_thread.join();}
}
};

Expand Down Expand Up @@ -211,6 +259,39 @@ class Recorder
rosbag2_py::Recorder::cancel();
});

#ifdef _WIN32
MichaelOrlov marked this conversation as resolved.
Show resolved Hide resolved
// According to the
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
// SIGINT is not supported for any Win32 application. When a CTRL+C interrupt occurs,
// Win32 operating systems generate a new thread to specifically handle that interrupt.
// Therefore, need to use native Windows control event handler as analog for the SIGINT.

// Enable default CTRL+C handler first. This is workaround and needed for the cases when
// process created with CREATE_NEW_PROCESS_GROUP flag. Without it, installing custom Ctrl+C
// handler will not work.
if (!SetConsoleCtrlHandler(nullptr, false)) {
std::cerr << "Rosbag2 recorder error: Failed to enable default CTL+C handler.\n";
}
// Installing our own control handler
auto CtrlHandler = [](DWORD fdwCtrlType) -> BOOL {
switch (fdwCtrlType) {
case CTRL_C_EVENT:
case CTRL_BREAK_EVENT:
case CTRL_CLOSE_EVENT:
rosbag2_py::Recorder::cancel();
return TRUE;
case CTRL_SHUTDOWN_EVENT:
rosbag2_py::Recorder::cancel();
return TRUE;
default:
return FALSE;
}
};
if (!SetConsoleCtrlHandler(CtrlHandler, TRUE)) {
std::cerr << "Rosbag2 recorder error: Could not set control handler.\n";
}
#endif // #ifdef _WIN32

try {
exit_ = false;
auto exec = std::make_unique<rclcpp::executors::SingleThreadedExecutor>();
Expand Down Expand Up @@ -251,6 +332,13 @@ class Recorder
if (old_sigint_handler != SIG_ERR) {
std::signal(SIGTERM, old_sigint_handler);
}
#ifdef _WIN32
// Remove CtrlHandler from ConsoleCtrl handlers
SetConsoleCtrlHandler(CtrlHandler, FALSE);
if (!SetConsoleCtrlHandler(nullptr, false)) {
std::cerr << "Rosbag2 recorder error: Failed to enable default CTL+C handler.\n";
}
#endif // #ifdef _WIN32
throw;
}
// Return old signal handlers
Expand All @@ -260,6 +348,13 @@ class Recorder
if (old_sigint_handler != SIG_ERR) {
std::signal(SIGTERM, old_sigint_handler);
}
#ifdef _WIN32
// Remove CtrlHandler from ConsoleCtrl handlers
SetConsoleCtrlHandler(CtrlHandler, FALSE);
if (!SetConsoleCtrlHandler(nullptr, false)) {
std::cerr << "Rosbag2 recorder error: Failed to enable default CTL+C handler.\n";
}
#endif // #ifdef _WIN32
}

static void cancel()
Expand Down
18 changes: 18 additions & 0 deletions rosbag2_test_common/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -42,8 +42,26 @@ install(
DESTINATION include/${PROJECT_NAME})

if(BUILD_TESTING)
find_package(ament_cmake_gmock REQUIRED)
find_package(ament_lint_auto REQUIRED)
find_package(rcpputils REQUIRED)
ament_lint_auto_find_test_dependencies()

add_executable(loop_with_ctrl_c_handler test/rosbag2_test_common/loop_with_ctrl_c_handler.cpp)
install(
TARGETS loop_with_ctrl_c_handler
EXPORT export_loop_with_ctrl_c_handler
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
)

ament_add_gmock(test_process_execution_helpers
test/rosbag2_test_common/test_process_execution_helpers.cpp
WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR})
if(TARGET test_process_execution_helpers)
target_link_libraries(test_process_execution_helpers ${PROJECT_NAME})
endif()
endif()

ament_python_install_package(${PROJECT_NAME})
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <gmock/gmock.h>

#include <direct.h>
#include <Windows.h>
#include <windows.h>

#include <chrono>
#include <csignal>
Expand All @@ -28,6 +28,32 @@

using namespace ::testing; // NOLINT

namespace
{
std::string get_last_error_str()
{
LPVOID lp_msg_buf;
DWORD err_code = GetLastError();
std::string result_str("Error code:" + std::to_string(err_code) + ". Error message: ");

DWORD buff_len = FormatMessage(
FORMAT_MESSAGE_ALLOCATE_BUFFER |
FORMAT_MESSAGE_FROM_SYSTEM |
FORMAT_MESSAGE_IGNORE_INSERTS,
NULL,
err_code,
MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
(LPTSTR) &lp_msg_buf,
0, NULL);
if (buff_len) {
LPCSTR lpc_msg_str = (LPCSTR)(lp_msg_buf);
result_str.append(std::string(lpc_msg_str, lpc_msg_str + buff_len));
}
LocalFree(lp_msg_buf);
return result_str;
}
} // namespace

struct Process
{
PROCESS_INFORMATION process_info;
Expand All @@ -46,7 +72,10 @@ PROCESS_INFORMATION create_process(TCHAR * command, const char * path = nullptr)
nullptr,
nullptr,
false,
0,
// Create process suspended and resume it after adding to the newly created job. Otherwise,
// there is a potential race condition where newly created process starts a subprocess
// before we've called AssignProcessToJobObject();
CREATE_NEW_PROCESS_GROUP | CREATE_SUSPENDED,
nullptr,
path,
&start_up_info,
Expand All @@ -73,8 +102,9 @@ int execute_and_wait_until_completion(const std::string & command, const std::st
const_char_to_tchar(command.c_str(), command_char);

auto process = create_process(command_char, path.c_str());
DWORD exit_code = 259; // 259 is the code one gets if the process is still active.
while (exit_code == 259) {
ResumeThread(process.hThread);
DWORD exit_code = STILL_ACTIVE;
while (exit_code == STILL_ACTIVE) {
EXPECT_TRUE(GetExitCodeProcess(process.hProcess, &exit_code));
std::this_thread::sleep_for(std::chrono::milliseconds(10));
}
Expand All @@ -97,6 +127,7 @@ ProcessHandle start_execution(const std::string & command)
auto process_info = create_process(command_char);

AssignProcessToJobObject(h_job, process_info.hProcess);
ResumeThread(process_info.hThread);
Process process;
process.process_info = process_info;
process.job_handle = h_job;
Expand All @@ -117,12 +148,12 @@ bool wait_until_completion(
DWORD exit_code = 0;
std::chrono::steady_clock::time_point const start = std::chrono::steady_clock::now();
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
// 259 indicates that the process is still active
while (exit_code == 259 && std::chrono::steady_clock::now() - start < timeout) {
while (exit_code == STILL_ACTIVE && std::chrono::steady_clock::now() - start < timeout) {
std::this_thread::sleep_for(std::chrono::milliseconds(10));
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
}
return exit_code != 259;
EXPECT_EQ(exit_code, 0);
return exit_code != STILL_ACTIVE;
}

/// @brief Force to stop process with signal if it's currently running
Expand All @@ -135,16 +166,39 @@ void stop_execution(
std::chrono::duration<double> timeout = std::chrono::seconds(10))
{
// Match the Unix version by allowing for int signum argument - however Windows does not have
// Linux signals in the same way, so there isn't a 1:1 mapping to dispatch e.g. SIGTERM
DWORD exit_code;
// Linux signals in the same way, so there isn't a 1:1 mapping to dispatch e.g. SIGINT or SIGTERM
DWORD exit_code = STILL_ACTIVE;
EXPECT_TRUE(GetExitCodeProcess(handle.process_info.hProcess, &exit_code));
// 259 indicates that the process is still active: we want to make sure that the process is
// still running properly before killing it.
if (exit_code == 259) {
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_C_EVENT, handle.process_info.dwThreadId));
// Make sure that the process is still running properly before stopping it.
if (exit_code == STILL_ACTIVE) {
switch (signum) {
// According to the
// https://learn.microsoft.com/en-us/cpp/c-runtime-library/reference/signal?view=msvc-170
// SIGINT is not supported for any Win32 application.
// Need to use native Windows control event instead.
case SIGINT:
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_C_EVENT, handle.process_info.dwProcessId)) <<
get_last_error_str();
break;
case SIGBREAK:
EXPECT_TRUE(GenerateConsoleCtrlEvent(CTRL_BREAK_EVENT, handle.process_info.dwProcessId)) <<
get_last_error_str();
break;
case SIGTERM:
// The CTRL_CLOSE_EVENT is analog of the SIGTERM from POSIX. Windows sends CTRL_CLOSE_EVENT
// to all processes attached to a console when the user closes the console (either by
// clicking Close on the console window's window menu, or by clicking the End Task
// button command from Task Manager). Although according to the
// https://learn.microsoft.com/en-us/windows/console/generateconsolectrlevent the
// GenerateConsoleCtrlEvent doesn't support sending CTRL_CLOSE_EVENT. There are no way to
// directly send CTRL_CLOSE_EVENT to the process in the same console application.
// Therefore, adding SIGTERM to the unsupported events.
default:
throw std::runtime_error("Unsupported signum: " + std::to_string(signum));
}
bool process_finished = wait_until_completion(handle, timeout);
if (!process_finished) {
std::cerr << "Testing process " << handle.process_info.hProcess <<
std::cerr << "Testing process " << handle.process_info.dwProcessId <<
" hangout. Killing it with TerminateProcess(..) \n";
EXPECT_TRUE(TerminateProcess(handle.process_info.hProcess, 2));
EXPECT_TRUE(process_finished);
Expand Down
1 change: 1 addition & 0 deletions rosbag2_test_common/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -23,6 +23,7 @@

<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<test_depend>rcpputils</test_depend>

<export>
<build_type>ament_cmake</build_type>
Expand Down
Loading
Loading