File tree Expand file tree Collapse file tree 8 files changed +64
-24
lines changed
demo_nodes_py/demo_nodes_py
quality_of_service_demo/rclpy/quality_of_service_demo_py Expand file tree Collapse file tree 8 files changed +64
-24
lines changed Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
from example_interfaces .srv import AddTwoInts
16
18
17
19
import rclpy
20
+ from rclpy .executors import ExternalShutdownException
18
21
from rclpy .node import Node
19
22
20
23
@@ -40,11 +43,13 @@ def main(args=None):
40
43
rclpy .spin (node )
41
44
except KeyboardInterrupt :
42
45
pass
43
-
44
- # Destroy the node explicitly
45
- # (optional - Done automatically when node is garbage collected)
46
- node .destroy_node ()
47
- rclpy .shutdown ()
46
+ except ExternalShutdownException :
47
+ sys .exit (1 )
48
+ finally :
49
+ # Destroy the node explicitly
50
+ # (optional - Done automatically when node is garbage collected)
51
+ rclpy .try_shutdown ()
52
+ node .destroy_node ()
48
53
49
54
50
55
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
import rclpy
18
+ from rclpy .executor import ExternalShutdownException
16
19
from rclpy .node import Node
17
20
18
21
from std_msgs .msg import String
@@ -36,9 +39,11 @@ def main(args=None):
36
39
rclpy .spin (node )
37
40
except KeyboardInterrupt :
38
41
pass
39
-
40
- node .destroy_node ()
41
- rclpy .shutdown ()
42
+ except ExternalShutdownException :
43
+ sys .exit (1 )
44
+ finally :
45
+ node .destroy_node ()
46
+ rclpy .try_shutdown ()
42
47
43
48
44
49
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
import rclpy
18
+ from rclpy .executors import ExternalShutdownException
16
19
from rclpy .node import Node
17
20
18
21
from std_msgs .msg import String
@@ -44,9 +47,11 @@ def main(args=None):
44
47
rclpy .spin (node )
45
48
except KeyboardInterrupt :
46
49
pass
47
-
48
- node .destroy_node ()
49
- rclpy .shutdown ()
50
+ except ExternalShutdownException :
51
+ sys .exit (1 )
52
+ finally :
53
+ rclpy .try_shutdown ()
54
+ node .destroy_node ()
50
55
51
56
52
57
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
import argparse
15
+ import sys
15
16
16
17
from quality_of_service_demo_py .common_nodes import Listener
17
18
from quality_of_service_demo_py .common_nodes import Talker
18
19
19
20
import rclpy
20
21
from rclpy .duration import Duration
22
+ from rclpy .executors import ExternalShutdownException
21
23
from rclpy .executors import SingleThreadedExecutor
22
24
from rclpy .logging import get_logger
23
25
from rclpy .qos import QoSProfile
@@ -68,9 +70,14 @@ def main(args=None):
68
70
executor = SingleThreadedExecutor ()
69
71
executor .add_node (listener )
70
72
executor .add_node (talker )
71
- executor .spin ()
72
-
73
- rclpy .shutdown ()
73
+ try :
74
+ executor .spin ()
75
+ except KeyboardInterrupt :
76
+ pass
77
+ except ExternalShutdownException :
78
+ sys .exit (1 )
79
+ finally :
80
+ rclpy .try_shutdown ()
74
81
75
82
76
83
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 20
20
21
21
import rclpy
22
22
from rclpy .duration import Duration
23
+ from rclpy .executors import ExternalShutdownException
23
24
from rclpy .executors import SingleThreadedExecutor
24
25
from rclpy .logging import get_logger
25
26
from rclpy .qos import QoSDurabilityPolicy
@@ -131,7 +132,7 @@ def main(args=None):
131
132
print ()
132
133
print (exc , end = '\n \n ' )
133
134
print ('Please try this demo using a different RMW implementation' )
134
- return - 1
135
+ return 1
135
136
136
137
executor = SingleThreadedExecutor ()
137
138
executor .add_node (listener )
@@ -142,8 +143,10 @@ def main(args=None):
142
143
executor .spin_once ()
143
144
except KeyboardInterrupt :
144
145
pass
145
-
146
- rclpy .shutdown ()
146
+ except ExternalShutdownException :
147
+ return 1
148
+ finally :
149
+ rclpy .try_shutdown ()
147
150
148
151
return 0
149
152
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
import rclpy
18
+ from rclpy .executors import ExternalShutdownException
16
19
from rclpy .executors import SingleThreadedExecutor
17
20
from rclpy .node import Node
18
21
from rclpy .qos_event import SubscriptionEventCallbacks
@@ -68,8 +71,10 @@ def main():
68
71
executor .spin ()
69
72
except KeyboardInterrupt :
70
73
pass
74
+ except ExternalShutdownException :
75
+ sys .exit (1 )
71
76
finally :
72
- rclpy .shutdown ()
77
+ rclpy .try_shutdown ()
73
78
74
79
75
80
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
import rclpy
18
+ from rclpy .executors import ExternalShutdownException
16
19
from rclpy .node import Node
17
20
from rclpy .qos_overriding_options import QosCallbackResult
18
21
from rclpy .qos_overriding_options import QoSOverridingOptions
@@ -52,9 +55,11 @@ def main(args=None):
52
55
rclpy .spin (node )
53
56
except KeyboardInterrupt :
54
57
pass
55
-
56
- node .destroy_node ()
57
- rclpy .shutdown ()
58
+ except ExternalShutdownException :
59
+ sys .exit (1 )
60
+ finally :
61
+ rclpy .try_shutdown ()
62
+ node .destroy_node ()
58
63
59
64
60
65
if __name__ == '__main__' :
Original file line number Diff line number Diff line change 12
12
# See the License for the specific language governing permissions and
13
13
# limitations under the License.
14
14
15
+ import sys
16
+
15
17
import rclpy
18
+ from rclpy .executors import ExternalShutdownException
16
19
from rclpy .node import Node
17
20
from rclpy .qos_overriding_options import QosCallbackResult
18
21
from rclpy .qos_overriding_options import QoSOverridingOptions
@@ -60,9 +63,11 @@ def main(args=None):
60
63
rclpy .spin (node )
61
64
except KeyboardInterrupt :
62
65
pass
63
-
64
- node .destroy_node ()
65
- rclpy .shutdown ()
66
+ except ExternalShutdownException :
67
+ sys .exit (1 )
68
+ finally :
69
+ rclpy .try_shutdown ()
70
+ node .destroy_node ()
66
71
67
72
68
73
if __name__ == '__main__' :
You can’t perform that action at this time.
0 commit comments