Skip to content

Commit

Permalink
Remove member function FieldOperatorApplication::shutdownAutoware
Browse files Browse the repository at this point in the history
Signed-off-by: yamacir-kit <[email protected]>
  • Loading branch information
yamacir-kit committed Dec 16, 2024
1 parent 5c65f27 commit 2400c42
Show file tree
Hide file tree
Showing 2 changed files with 75 additions and 81 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -162,8 +162,6 @@ struct FieldOperatorApplication : public rclcpp::Node,

auto spinSome() -> void;

auto shutdownAutoware() -> void;

auto engage() -> void;

auto engageable() const -> bool;
Expand Down
154 changes: 75 additions & 79 deletions external/concealer/src/field_operator_application.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -212,7 +212,81 @@ FieldOperatorApplication::FieldOperatorApplication(const pid_t pid)

FieldOperatorApplication::~FieldOperatorApplication()
{
shutdownAutoware();
if (is_stop_requested.store(true);
process_id != 0 && not std::exchange(is_autoware_exited, true)) {
const auto sigset = [this]() {
if (auto signal_set = sigset_t();
sigemptyset(&signal_set) or sigaddset(&signal_set, SIGCHLD)) {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(errno, std::system_category()).what());
std::exit(EXIT_FAILURE);
} else if (auto error = pthread_sigmask(SIG_BLOCK, &signal_set, nullptr)) {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(error, std::system_category()).what());
std::exit(EXIT_FAILURE);
} else {
return signal_set;
}
}();

const auto timeout = []() {
auto sigterm_timeout = [](auto value) {
auto node = rclcpp::Node("get_parameter_sigterm_timeout", "simulation");
node.declare_parameter<int>("sigterm_timeout", value);
node.get_parameter<int>("sigterm_timeout", value);
return value;
};
auto timeout = timespec();
timeout.tv_sec = sigterm_timeout(5);
timeout.tv_nsec = 0;
return timeout;
}();

if (::kill(process_id, SIGINT); sigtimedwait(&sigset, nullptr, &timeout) < 0) {
switch (errno) {
case EINTR:
/*
The wait was interrupted by an unblocked, caught signal. It shall
be documented in system documentation whether this error causes
these functions to fail.
*/
RCLCPP_ERROR_STREAM(
get_logger(),
"The wait for Autoware launch process termination was interrupted by an unblocked, "
"caught signal.");
break;

case EAGAIN:
/*
No signal specified by set was generated within the specified
timeout period.
*/
RCLCPP_ERROR_STREAM(get_logger(), "Autoware launch process does not respond. Kill it.");
killpg(process_id, SIGKILL);
break;

default:
case EINVAL:
/*
The timeout argument specified a tv_nsec value less than zero or
greater than or equal to 1000 million.
*/
RCLCPP_ERROR_STREAM(
get_logger(),
"The parameter sigterm_timeout specified a value less than zero or greater than or "
"equal to 1000 million.");
break;
}
}

if (int status = 0; waitpid(process_id, &status, 0) < 0) {
if (errno == ECHILD) {
RCLCPP_ERROR_STREAM(
get_logger(), "Try to wait for the autoware process but it was already exited.");
} else {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(errno, std::system_category()).what());
}
}
}

// All tasks should be complete before the services used in them will be deinitialized.
task_queue.stopAndJoin();
}
Expand Down Expand Up @@ -484,82 +558,4 @@ auto FieldOperatorApplication::spinSome() -> void
rclcpp::spin_some(get_node_base_interface());
}
}

auto FieldOperatorApplication::shutdownAutoware() -> void
{
if (is_stop_requested.store(true);
process_id != 0 && not std::exchange(is_autoware_exited, true)) {
const auto sigset = [this]() {
if (auto signal_set = sigset_t();
sigemptyset(&signal_set) or sigaddset(&signal_set, SIGCHLD)) {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(errno, std::system_category()).what());
std::exit(EXIT_FAILURE);
} else if (auto error = pthread_sigmask(SIG_BLOCK, &signal_set, nullptr)) {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(error, std::system_category()).what());
std::exit(EXIT_FAILURE);
} else {
return signal_set;
}
}();

const auto timeout = []() {
auto sigterm_timeout = [](auto value) {
auto node = rclcpp::Node("get_parameter_sigterm_timeout", "simulation");
node.declare_parameter<int>("sigterm_timeout", value);
node.get_parameter<int>("sigterm_timeout", value);
return value;
};
auto timeout = timespec();
timeout.tv_sec = sigterm_timeout(5);
timeout.tv_nsec = 0;
return timeout;
}();

if (::kill(process_id, SIGINT); sigtimedwait(&sigset, nullptr, &timeout) < 0) {
switch (errno) {
case EINTR:
/*
The wait was interrupted by an unblocked, caught signal. It shall
be documented in system documentation whether this error causes
these functions to fail.
*/
RCLCPP_ERROR_STREAM(
get_logger(),
"The wait for Autoware launch process termination was interrupted by an unblocked, "
"caught signal.");
break;

case EAGAIN:
/*
No signal specified by set was generated within the specified
timeout period.
*/
RCLCPP_ERROR_STREAM(get_logger(), "Autoware launch process does not respond. Kill it.");
killpg(process_id, SIGKILL);
break;

default:
case EINVAL:
/*
The timeout argument specified a tv_nsec value less than zero or
greater than or equal to 1000 million.
*/
RCLCPP_ERROR_STREAM(
get_logger(),
"The parameter sigterm_timeout specified a value less than zero or greater than or "
"equal to 1000 million.");
break;
}
}

if (int status = 0; waitpid(process_id, &status, 0) < 0) {
if (errno == ECHILD) {
RCLCPP_ERROR_STREAM(
get_logger(), "Try to wait for the autoware process but it was already exited.");
} else {
RCLCPP_ERROR_STREAM(get_logger(), std::system_error(errno, std::system_category()).what());
}
}
}
}
} // namespace concealer

0 comments on commit 2400c42

Please sign in to comment.