Skip to content
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
18 changes: 16 additions & 2 deletions buoy_api_py/buoy_api/interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -310,7 +310,7 @@ def __init__(self, node_name, wait_for_services=False, check_for_services=True,
pass
self.get_logger().info('Found all required services.')

def spin(self):
def spin(self, sys_exit=False):
"""
Set up a `MultiThreadedExecutor` and spin the node (blocking).

Expand All @@ -320,7 +320,21 @@ def spin(self):
"""
executor = MultiThreadedExecutor()
executor.add_node(self)
executor.spin()
try:
executor.spin()
except KeyboardInterrupt:
if rclpy.ok():
self.get_logger().info('Shutting down (SIGINT)...')
else:
print(f'[{self.get_name()}] Shutting down (SIGINT)...')
finally:
executor.remove_node(self)
self.destroy_node()
if exit:
if rclpy.ok():
rclpy.shutdown()
import sys
sys.exit(0)

def wait_for_services(self):
# TODO(andermi)
Expand Down
6 changes: 1 addition & 5 deletions sim_pblog/sim_pblog/sim_pblog.py
Original file line number Diff line number Diff line change
Expand Up @@ -404,11 +404,7 @@ def main():
rclpy.init(args=extras)
pblog = WECLogger(args.loghome if args.loghome else loghome_arg.default,
args.logdir if args.logdir else logdir_arg.default)
import time
while rclpy.ok():
rclpy.spin_once(pblog)
time.sleep(1./1000.)
rclpy.shutdown()
pblog.spin(sys_exit=True)


if __name__ == '__main__':
Expand Down