From 436c594cd81186324ec77eacd1e8284dcda76f81 Mon Sep 17 00:00:00 2001 From: Himsara Gallege Date: Wed, 1 Sep 2021 07:36:36 +0000 Subject: [PATCH 1/3] Added Basic Functions --- heartbeat_listener.py | 63 +++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 63 insertions(+) create mode 100644 heartbeat_listener.py diff --git a/heartbeat_listener.py b/heartbeat_listener.py new file mode 100644 index 0000000..db604ad --- /dev/null +++ b/heartbeat_listener.py @@ -0,0 +1,63 @@ +#!/usr/bin/env python3 + +#--**--..--**--..--**--..--**--..--**--..--**--..--**--..--**--..--**-- +# +# Currently, it will flash the LED red if no heartbeat found +# +# Author: Harrison +# Last modified 22/03/21 by: Harrison +# Translated to ROS2 by: Himsara +# +# Subscribed topics: +# - /base/heartbeat +#--..--**--..--**--..--**--..--**--..--**--..--**--..--**--..--**--..-- + +''' +NOVA ROVER TEAM +This node listens to heartbeat from base and performs actions if not received +Currently, it will flash the LED red if no heartbeat found +Author: Himsara Gallege +''' + +import rclpy +from rclpy.node import Node + +from std_msgs.msg import String + +class HeartbeatSub(Node): + # Store whether or not a beat has been found + beat = False + beat_count = 0 + + # The time out and loop counts + LOOP_HERTZ = 50 + TIME_OUT = 25 + + # The initialisation function + def __init__ (self): + print("Initialising Heartbeat Subscriber class.") + super().__init__('HeartbeatSub') + self.subscription = self.create_subscription(String, 'topic', self.callback_func, 10) + self.subscription # prevent unused variable warning + + # Run the check node for seeing if heartbeat exists + self.check_heartbeat() + + # Called when received heartbeat information + def received_cb (self, data): + self.heartbeat() + self.beat_count = 0 + + + # When heartbeat times out + def no_heartbeat (self): + self.beat = False + print("\033[1;31;48mNo Heartbeart Detected\033[0;0m") + + + # When heartbeat returns + def heartbeat (self): + if not self.beat: + print("\033[1;31;44mHeartbeat Returned\033[0;0m") + self.beat = True + From 50f807e15ee55379d0f31ea76e87ce1e0665f886 Mon Sep 17 00:00:00 2001 From: Himsara Gallege Date: Wed, 1 Sep 2021 08:11:29 +0000 Subject: [PATCH 2/3] Added check heartbeat function --- heartbeat_listener.py | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/heartbeat_listener.py b/heartbeat_listener.py index db604ad..51f0432 100644 --- a/heartbeat_listener.py +++ b/heartbeat_listener.py @@ -36,18 +36,25 @@ class HeartbeatSub(Node): # The initialisation function def __init__ (self): print("Initialising Heartbeat Subscriber class.") - super().__init__('HeartbeatSub') - self.subscription = self.create_subscription(String, 'topic', self.callback_func, 10) - self.subscription # prevent unused variable warning - # Run the check node for seeing if heartbeat exists - self.check_heartbeat() + # ROS initialisation + super().__init__('HeartbeatSub') + self.subscription = self.create_subscription(Empty, 'base/heartbeat', self.callback_func, 10) + + # Create timer to run checkheartbeat frequently + self.timer = self.create_timer(0.1, self.check_heartbeat) # Called when received heartbeat information def received_cb (self, data): self.heartbeat() self.beat_count = 0 + def check_heartbeat(self): + if self.beat_count <= TIME_OUT: + self.beat_count += 1 + else: + self.no_heartbeat() + # When heartbeat times out def no_heartbeat (self): From 9033ddebdb76f920453ad4179fc242c3c9877cc7 Mon Sep 17 00:00:00 2001 From: Himsara Gallege Date: Wed, 1 Sep 2021 21:56:58 +0000 Subject: [PATCH 3/3] Added paramter and description --- heartbeat_listener.py | 18 +++++++++++++----- 1 file changed, 13 insertions(+), 5 deletions(-) diff --git a/heartbeat_listener.py b/heartbeat_listener.py index 51f0432..6b91909 100644 --- a/heartbeat_listener.py +++ b/heartbeat_listener.py @@ -40,12 +40,17 @@ def __init__ (self): # ROS initialisation super().__init__('HeartbeatSub') self.subscription = self.create_subscription(Empty, 'base/heartbeat', self.callback_func, 10) + + y_parameter_descriptor = ParameterDescriptor(description='Rover Heartbeat Parameter') + + # Declare Parameter + self.declare_parameter('/rover/heartbeat') # Create timer to run checkheartbeat frequently self.timer = self.create_timer(0.1, self.check_heartbeat) # Called when received heartbeat information - def received_cb (self, data): + def callback_func (self, data): self.heartbeat() self.beat_count = 0 @@ -55,16 +60,19 @@ def check_heartbeat(self): else: self.no_heartbeat() + # Set parameter + self.set_parameters([Parameter('/rover/heartbeat', Parameter.Type.BOOL, self.beat_count <= TIME_OUT)]) + # When heartbeat times out def no_heartbeat (self): - self.beat = False + self.beat = False print("\033[1;31;48mNo Heartbeart Detected\033[0;0m") # When heartbeat returns def heartbeat (self): - if not self.beat: - print("\033[1;31;44mHeartbeat Returned\033[0;0m") - self.beat = True + if not self.beat: + print("\033[1;31;44mHeartbeat Returned\033[0;0m") + self.beat = True