12
12
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
13
13
NODE: heartbeat_monitor
14
14
TOPICS:
15
- - None
15
+ - subscribes to /control/heartbeat with msg Empty
16
16
SERVICES:
17
- - None
17
+ - calls 'rover_emergency_client'
18
18
ACTIONS:
19
19
- None
20
20
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
21
21
PACKAGE: tutorials
22
22
AUTHOR(S): Josh Cherubino
23
23
CREATION: 31/08/21
24
- EDITED: 31/08 /21
24
+ EDITED: 01/09 /21
25
25
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
26
26
TODO:
27
27
- 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
29
30
~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
30
31
"""
31
32
@@ -75,8 +76,6 @@ def __init__(self) -> None:
75
76
76
77
#create event callbacks to be triggerred on deadline missed
77
78
#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
80
79
subscription_event_callbacks = \
81
80
rclpy .qos_event .SubscriptionEventCallbacks (deadline = self .beat_missed ,
82
81
liveliness = self .check_beat_lost )
@@ -86,15 +85,14 @@ def __init__(self) -> None:
86
85
self .beat_received , qos_profile , event_callbacks = subscription_event_callbacks )
87
86
88
87
#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
98
96
self .get_logger ().info ('Heartbeat monitor started' )
99
97
100
98
def beat_received (self , msg : Empty ) -> None :
@@ -106,27 +104,26 @@ def beat_received(self, msg: Empty) -> None:
106
104
"""
107
105
#if heartbeat just re-gained, log that it has been detected
108
106
#otherwise do nothing
109
- if not self .beat :
107
+ if self . state != self .BEAT_OK :
110
108
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 :
114
111
#call client to resume rover actions
115
112
#self.rover_emergency_client.call_async(Msg(RESUME))
116
113
self .get_logger ().info ('Resuming rover' )
117
- self .halted = False
114
+ #update state
115
+ self .state = self .BEAT_OK
118
116
119
117
def beat_missed (self , info : rclpy .qos_event .QoSRequestedDeadlineMissedInfo ) -> None :
120
118
"""
121
119
Event callback run when publisher misses deadline required by QoS profile.
122
120
Sets heartbeat as lost and logs warning
123
121
:param info: Information about the requested deadline miss
124
122
"""
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 :
128
125
self .get_logger ().warn ('Heartbeat missed. Total misses: {}' .format (info .total_count ))
129
- self .beat = False
126
+ self .state = self . BEAT_MISSED
130
127
131
128
def check_beat_lost (self , info : rclpy .qos_event .QoSLivelinessChangedInfo ) -> None :
132
129
"""
@@ -141,8 +138,7 @@ def check_beat_lost(self, info: rclpy.qos_event.QoSLivelinessChangedInfo) -> Non
141
138
#call appropriate service to halt rovers motion here
142
139
#i.e. self.future = self.rover_emergency_client.call_async(Msg(HALT))
143
140
#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
146
142
self .get_logger ().error ('Heartbeat lost. Halting rover' )
147
143
148
144
def main (args = None ):
0 commit comments