Skip to content

Commit

Permalink
Merge pull request #17 from ros2/launch_package
Browse files Browse the repository at this point in the history
add rclcpp::shutdown() function
  • Loading branch information
dirk-thomas committed Mar 28, 2015
2 parents bf61c2d + e720daf commit 9064648
Show file tree
Hide file tree
Showing 2 changed files with 10 additions and 0 deletions.
1 change: 1 addition & 0 deletions rclcpp/include/rclcpp/rclcpp.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -60,6 +60,7 @@ using rclcpp::timer::TimerBase;
using rclcpp::timer::WallTimer;
typedef rclcpp::context::Context::SharedPtr ContextSharedPtr;
using rclcpp::utilities::ok;
using rclcpp::utilities::shutdown;
using rclcpp::utilities::init;
using rclcpp::utilities::sleep_for;

Expand Down
9 changes: 9 additions & 0 deletions rclcpp/include/rclcpp/utilities.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -127,6 +127,15 @@ ok()
return ::g_signal_status == 0;
}

void
shutdown()
{
g_signal_status = SIGINT;
rmw_trigger_guard_condition(g_sigint_guard_cond_handle);
g_interrupt_condition_variable.notify_all();
}


rmw_guard_condition_t *
get_global_sigint_guard_condition()
{
Expand Down

0 comments on commit 9064648

Please sign in to comment.