Skip to content

Commit 03d565d

Browse files
committed
Update monitor to use single state variable
Instead of 2 flags, use a state variable to track from 3 possible states: BEAT_OK, BEAT_MISSED, and BEAT_LOST.
1 parent cd4751a commit 03d565d

File tree

1 file changed

+22
-26
lines changed

1 file changed

+22
-26
lines changed

tutorials/heartbeat_monitor.py

+22-26
Original file line numberDiff line numberDiff line change
@@ -12,20 +12,21 @@
1212
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
1313
NODE: heartbeat_monitor
1414
TOPICS:
15-
- None
15+
- subscribes to /control/heartbeat with msg Empty
1616
SERVICES:
17-
- None
17+
- calls 'rover_emergency_client'
1818
ACTIONS:
1919
- None
2020
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2121
PACKAGE: tutorials
2222
AUTHOR(S): Josh Cherubino
2323
CREATION: 31/08/21
24-
EDITED: 31/08/21
24+
EDITED: 01/09/21
2525
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
2626
TODO:
2727
- tune BEAT_MISSED_DEADLINE and BEAT_LOST_DURATION values
28-
- Instantiate and call client once node has been created
28+
- Instantiate and call emergency client once node has been created.
29+
- Update docstring to match correct client name
2930
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
3031
"""
3132

@@ -75,8 +76,6 @@ def __init__(self) -> None:
7576

7677
#create event callbacks to be triggerred on deadline missed
7778
#and lease duration execeeded (liveliness lost)
78-
#this isn't documented for some reason.
79-
#see source https://github.com/ros2/rclpy/blob/98707238ad2564e28cbc987fc3a31ed9a1c86243/rclpy/rclpy/qos_event.py
8079
subscription_event_callbacks = \
8180
rclpy.qos_event.SubscriptionEventCallbacks(deadline=self.beat_missed,
8281
liveliness=self.check_beat_lost)
@@ -86,15 +85,14 @@ def __init__(self) -> None:
8685
self.beat_received, qos_profile, event_callbacks=subscription_event_callbacks)
8786

8887
#flag to track if we have the heart beat.
89-
#Assume no heartbeat initially
90-
self.beat = False
91-
#flag to track if we have halted the rover previously
92-
self.halted = True
93-
94-
#create client instance here
95-
96-
#and initially halt rover until we confirm we can receive a heartbeat
97-
88+
#define possible node states
89+
self.BEAT_OK = 0
90+
self.BEAT_MISSED = 1
91+
self.BEAT_LOST = 2
92+
#Assume beat lost initially
93+
self.state = self.BEAT_LOST
94+
#TODO: create client instance here
95+
#TODO: initially halt rover until we confirm we can receive a heartbeat
9896
self.get_logger().info('Heartbeat monitor started')
9997

10098
def beat_received(self, msg: Empty) -> None:
@@ -106,27 +104,26 @@ def beat_received(self, msg: Empty) -> None:
106104
"""
107105
#if heartbeat just re-gained, log that it has been detected
108106
#otherwise do nothing
109-
if not self.beat:
107+
if self.state != self.BEAT_OK:
110108
self.get_logger().info('Heartbeat detected')
111-
self.beat = True
112-
#heart-beat regained
113-
if self.halted:
109+
#check if heart-beat just regained
110+
if self.state == self.BEAT_LOST:
114111
#call client to resume rover actions
115112
#self.rover_emergency_client.call_async(Msg(RESUME))
116113
self.get_logger().info('Resuming rover')
117-
self.halted = False
114+
#update state
115+
self.state = self.BEAT_OK
118116

119117
def beat_missed(self, info: rclpy.qos_event.QoSRequestedDeadlineMissedInfo) -> None:
120118
"""
121119
Event callback run when publisher misses deadline required by QoS profile.
122120
Sets heartbeat as lost and logs warning
123121
:param info: Information about the requested deadline miss
124122
"""
125-
#only log missed beat (to avoid spam where heartbeat completely lost) when
126-
#it was previously not lost
127-
if self.beat:
123+
#log missed beats when heart beat just missed or previously missed
124+
if self.state == self.BEAT_OK:
128125
self.get_logger().warn('Heartbeat missed. Total misses: {}'.format(info.total_count))
129-
self.beat = False
126+
self.state = self.BEAT_MISSED
130127

131128
def check_beat_lost(self, info: rclpy.qos_event.QoSLivelinessChangedInfo) -> None:
132129
"""
@@ -141,8 +138,7 @@ def check_beat_lost(self, info: rclpy.qos_event.QoSLivelinessChangedInfo) -> Non
141138
#call appropriate service to halt rovers motion here
142139
#i.e. self.future = self.rover_emergency_client.call_async(Msg(HALT))
143140
#set state to halted so we can resume when beat re-acquired
144-
self.halted = True
145-
self.beat = False
141+
self.state = self.BEAT_LOST
146142
self.get_logger().error('Heartbeat lost. Halting rover')
147143

148144
def main(args=None):

0 commit comments

Comments
 (0)