Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Cleanups in demo_nodes_py. #555

Merged
merged 1 commit into from
Jan 24, 2022
Merged
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
Original file line number Diff line number Diff line change
Expand Up @@ -36,7 +36,7 @@ def main(args=None):
node.get_logger().error('Exception while calling service: %r' % future.exception())

node.destroy_node()
rclpy.shutdown()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -41,7 +41,7 @@ def main(args=None):
break

node.destroy_node()
rclpy.shutdown()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,8 @@ def main(args=None):
finally:
# Destroy the node explicitly
# (optional - Done automatically when node is garbage collected)
rclpy.try_shutdown()
node.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
18 changes: 12 additions & 6 deletions demo_nodes_py/demo_nodes_py/topics/listener_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from rclpy.qos import QoSProfile
Expand Down Expand Up @@ -63,12 +64,17 @@ def main(argv=sys.argv[1:]):
node = ListenerQos(custom_qos_profile)

cycle_count = 0
while rclpy.ok() and cycle_count < args.number_of_cycles:
rclpy.spin_once(node)
cycle_count += 1

node.destroy_node()
rclpy.shutdown()
try:
while rclpy.ok() and cycle_count < args.number_of_cycles:
rclpy.spin_once(node)
cycle_count += 1
except KeyboardInterrupt:
pass
except ExternalShutdownException:
sys.exit(1)
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
22 changes: 15 additions & 7 deletions demo_nodes_py/demo_nodes_py/topics/listener_serialized.py
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,10 @@
# See the License for the specific language governing permissions and
# limitations under the License.

import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node

from std_msgs.msg import String
Expand All @@ -38,13 +41,18 @@ def main(args=None):

serialized_subscriber = SerializedSubscriber()

rclpy.spin(serialized_subscriber)

# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
serialized_subscriber.destroy_node()
rclpy.shutdown()
try:
rclpy.spin(serialized_subscriber)
except KeyboardInterrupt:
pass
except ExternalShutdownException:
sys.exit(1)
finally:
# Destroy the node explicitly
# (optional - otherwise it will be done automatically
# when the garbage collector destroys the node object)
serialized_subscriber.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
2 changes: 1 addition & 1 deletion demo_nodes_py/demo_nodes_py/topics/talker.py
Original file line number Diff line number Diff line change
Expand Up @@ -50,8 +50,8 @@ def main(args=None):
except ExternalShutdownException:
sys.exit(1)
finally:
rclpy.try_shutdown()
node.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down
18 changes: 12 additions & 6 deletions demo_nodes_py/demo_nodes_py/topics/talker_qos.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
import sys

import rclpy
from rclpy.executors import ExternalShutdownException
from rclpy.node import Node
from rclpy.qos import qos_profile_sensor_data
from rclpy.qos import QoSProfile
Expand Down Expand Up @@ -70,12 +71,17 @@ def main(argv=sys.argv[1:]):
node = TalkerQos(custom_qos_profile)

cycle_count = 0
while rclpy.ok() and cycle_count < args.number_of_cycles:
rclpy.spin_once(node)
cycle_count += 1

node.destroy_node()
rclpy.shutdown()
try:
while rclpy.ok() and cycle_count < args.number_of_cycles:
rclpy.spin_once(node)
cycle_count += 1
except KeyboardInterrupt:
pass
except ExternalShutdownException:
sys.exit(1)
finally:
node.destroy_node()
rclpy.try_shutdown()


if __name__ == '__main__':
Expand Down