Skip to content

Commit

Permalink
Add SIGTERM regression test, with fix commented out
Browse files Browse the repository at this point in the history
Signed-off-by: Emerson Knapp <eknapp@amazon.com>
  • Loading branch information
Emerson Knapp committed Jun 24, 2021
1 parent bb9c7ae commit 9896c99
Show file tree
Hide file tree
Showing 4 changed files with 23 additions and 3 deletions.
4 changes: 4 additions & 0 deletions rosbag2_py/src/rosbag2_py/_transport.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,6 +12,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.

#include <csignal>
#include <chrono>
#include <memory>
#include <string>
Expand Down Expand Up @@ -145,6 +146,9 @@ class Recorder
Recorder()
{
rclcpp::init(0, nullptr);
// std::signal(SIGTERM, [](int/* signal */) {
// rclcpp::shutdown();
// });
}

virtual ~Recorder()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,9 +59,9 @@ ProcessHandle start_execution(const std::string & command)
return process_id;
}

void stop_execution(const ProcessHandle & handle)
void stop_execution(const ProcessHandle & handle, int signum = SIGINT)
{
killpg(handle, SIGINT);
killpg(handle, signum);
int child_return_code;
waitpid(handle, &child_return_code, 0);
// this call will make sure that the process does execute without issues before it is killed by
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -104,8 +104,10 @@ ProcessHandle start_execution(const std::string & command)
return process;
}

void stop_execution(const ProcessHandle & handle)
void stop_execution(const ProcessHandle & handle, int/* signum = SIGINT*/)
{
// 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;
GetExitCodeProcess(handle.process_info.hProcess, &exit_code);
// 259 indicates that the process is still active: we want to make sure that the process is
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -162,6 +162,20 @@ TEST_F(RecordFixture, record_end_to_end_test) {
EXPECT_THAT(wrong_topic_messages, IsEmpty());
}

TEST_F(RecordFixture, record_end_to_end_exits_gracefully_on_sigterm) {
const std::string topic_name = "/test_sigterm";
auto message = get_messages_strings()[0];
message->string_value = "test";
rosbag2_test_common::PublicationManager pub_manager;
pub_manager.setup_publisher(topic_name, message, 10);
auto process_handle = start_execution(
"ros2 bag record --output " + root_bag_path_.string() + " " + topic_name);
wait_for_db();
pub_manager.run_publishers();
stop_execution(process_handle, SIGTERM);
wait_for_metadata();
}

// TODO(zmichaels11): Fix and enable this test on Windows.
// This tests depends on the ability to read the metadata file.
// Stopping the process on Windows does a hard kill and the metadata file is not written.
Expand Down

0 comments on commit 9896c99

Please sign in to comment.