|
5 | 5 | """
|
6 | 6 | import json
|
7 | 7 | from heapq import heappush, heappop
|
8 |
| -import logging |
9 | 8 | from pathlib import Path
|
10 | 9 | from threading import Condition, Event, Lock, Thread
|
11 | 10 | from typing import Callable
|
12 | 11 | from typing import Dict
|
13 | 12 | from typing import List
|
14 | 13 | from typing import Optional
|
15 |
| -from typing import Tuple |
16 | 14 |
|
17 | 15 | import kwcoco
|
18 | 16 | from builtin_interfaces.msg import Time
|
19 | 17 | import numpy as np
|
20 | 18 | import numpy.typing as npt
|
21 |
| -import rclpy |
22 | 19 | from rclpy.callback_groups import MutuallyExclusiveCallbackGroup
|
23 |
| -import rclpy.logging |
24 | 20 | from rclpy.node import Node
|
25 |
| -from rclpy.executors import MultiThreadedExecutor |
26 | 21 | import torch
|
27 | 22 |
|
28 | 23 | from angel_system.activity_classification.tcn_hpl.predict import (
|
|
39 | 34 | ObjectDetection2dSet,
|
40 | 35 | ActivityDetection,
|
41 | 36 | )
|
42 |
| -from angel_utils import declare_and_get_parameters, RateTracker |
| 37 | +from angel_utils import declare_and_get_parameters, make_default_main, RateTracker |
43 | 38 | from angel_utils.activity_classification import InputWindow, InputBuffer
|
44 | 39 | from angel_utils.conversion import time_to_int
|
45 | 40 | from angel_utils.object_detection import max_labels_and_confs
|
@@ -683,40 +678,16 @@ def _save_results(self):
|
683 | 678 |
|
684 | 679 | def destroy_node(self):
|
685 | 680 | log = self.get_logger()
|
| 681 | + log.info("Stopping node runtime") |
| 682 | + self.rt_stop() |
686 | 683 | with SimpleTimer("Shutting down runtime thread...", log.info):
|
687 | 684 | self._rt_active.clear() # make RT active flag "False"
|
688 | 685 | self._rt_thread.join()
|
689 | 686 | self._save_results()
|
690 | 687 | super().destroy_node()
|
691 | 688 |
|
692 | 689 |
|
693 |
| -def main(): |
694 |
| - logging.basicConfig( |
695 |
| - format="[%(levelname)s] [%(asctime)s] [%(name)s.%(funcName)s]: %(message)s" |
696 |
| - ) |
697 |
| - logging.getLogger().setLevel(logging.INFO) |
698 |
| - |
699 |
| - rclpy.init() |
700 |
| - log = rclpy.logging.get_logger("main") |
701 |
| - |
702 |
| - activity_classifier = ActivityClassifierTCN() |
703 |
| - |
704 |
| - executor = MultiThreadedExecutor(num_threads=4) |
705 |
| - executor.add_node(activity_classifier) |
706 |
| - try: |
707 |
| - executor.spin() |
708 |
| - except KeyboardInterrupt: |
709 |
| - log.info("Keyboard interrupt, shutting down.\n") |
710 |
| - finally: |
711 |
| - log.info("Stopping node runtime") |
712 |
| - activity_classifier.rt_stop() |
713 |
| - |
714 |
| - # Destroy the node explicitly |
715 |
| - # (optional - otherwise it will be done automatically |
716 |
| - # when the garbage collector destroys the node object) |
717 |
| - activity_classifier.destroy_node() |
718 |
| - |
719 |
| - rclpy.shutdown() |
| 690 | +main = make_default_main(ActivityClassifierTCN, multithreaded_executor=4) |
720 | 691 |
|
721 | 692 |
|
722 | 693 | if __name__ == "__main__":
|
|
0 commit comments