emergency_stop_monitor.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 #
3 # Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
4 #
5 # Licensed under the Apache License, Version 2.0 (the "License");
6 # you may not use this file except in compliance with the License.
7 # You may obtain a copy of the License at
8 #
9 # http://www.apache.org/licenses/LICENSE-2.0
10 #
11 # Unless required by applicable law or agreed to in writing, software
12 # distributed under the License is distributed on an "AS IS" BASIS,
13 # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14 # See the License for the specific language governing permissions and
15 # limitations under the License.
16 
17 
18 import sys
19 import copy
20 from enum import IntEnum
21 
22 import rospy
23 from sensor_msgs.msg import JointState
24 from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray
25 
26 from cob_msgs.msg import *
27 from cob_light.msg import LightMode, LightModes, SetLightModeGoal, SetLightModeAction
28 from cob_light.srv import StopLightMode, StopLightModeRequest
29 
30 from simple_script_server import *
32 
33 class EMState(IntEnum):
34  EM_UNKNOWN = -1
35  EM_FREE = 0
36  EM_BUTTON = 1
37  EM_BRAKE = 2
38  EM_LASER = 3
39  EM_WIRELESS = 4
40  EM_FALL = 5
41  EM_INTERNAL = 6
42 
43 
45  def __init__(self):
46  self.color = "None"
47  self.enable_sound = rospy.get_param("~enable_sound", False)
48  self.enable_light = rospy.get_param("~enable_light", False)
49  self.diagnostics_based = rospy.get_param("~diagnostics_based", False)
50  self.motion_based = rospy.get_param("~motion_based", False)
51  self.track_id_light = None
52 
53  if(self.enable_light):
54  if not rospy.has_param("~light_components"):
55  rospy.logwarn("parameter light_components does not exist on ROS Parameter Server, aborting...")
56  sys.exit(1)
57  self.light_components = rospy.get_param("~light_components")
58 
59  # set colors (also neccessary if self.enable_light is false)
60  self.color_error = rospy.get_param("~color_error","red")
61  self.color_warn = rospy.get_param("~color_warn","yellow")
62  self.color_ok = rospy.get_param("~color_ok","green")
63  self.color_off = rospy.get_param("~color_off","black")
64 
65  if(self.enable_sound):
66  if not rospy.has_param("~sound_components"):
67  rospy.logwarn("parameter sound_components does not exist on ROS Parameter Server, aborting...")
68  sys.exit(1)
69  self.sound_components = rospy.get_param("~sound_components")
70 
71  self.sound_em_button_released = rospy.get_param("~sound_em_button_released", "button released")
72  self.sound_em_button_issued = rospy.get_param("~sound_em_button_issued", "button issued")
73  self.sound_em_brake_released = rospy.get_param("~sound_em_brake_released", "brake released")
74  self.sound_em_brake_issued = rospy.get_param("~sound_em_brake_issued", "brake issued")
75  self.sound_em_laser_released = rospy.get_param("~sound_em_laser_released", "laser released")
76  self.sound_em_laser_issued = rospy.get_param("~sound_em_laser_issued", "laser issued")
77  self.sound_em_wireless_released = rospy.get_param("~sound_em_wireless_released", "wireless released")
78  self.sound_em_wireless_issued = rospy.get_param("~sound_em_wireless_issued", "wireless issued")
79  self.sound_em_fall_released = rospy.get_param("~sound_em_fall_released", "fall released")
80  self.sound_em_fall_issued = rospy.get_param("~sound_em_fall_issued", "fall issued")
81  self.sound_em_internal_released = rospy.get_param("~sound_em_internal_released", "internal released")
82  self.sound_em_internal_issued = rospy.get_param("~sound_em_internal_issued", "internal issued")
83 
84  rospy.Subscriber("/diagnostics_agg", DiagnosticArray, self.diagnostics_agg_callback, queue_size=1)
85  self.em_state = EMState.EM_UNKNOWN
86 
87  self.diag_status = -1
88  if(self.diagnostics_based):
89  rospy.Subscriber("/diagnostics_toplevel_state", DiagnosticStatus, self.diagnostics_callback, queue_size=1)
90  self.last_diag = rospy.get_rostime()
91 
92  self.motion_status = -1
93  if(self.motion_based):
94  rospy.Subscriber("/joint_states", JointState, self.jointstate_callback, queue_size=1)
95  self.last_vel = rospy.get_rostime()
96 
97  def diagnostics_agg_callback(self, msg):
98  diagnostics_errors = []
99  diagnostics_errors_detail = []
100 
101  #all diagnostics that have warning/error/stale
102  for status in msg.status:
103  if "Safety" in status.name:
104  if status.level > DiagnosticStatus.OK:
105  diagnostics_errors.append(status)
106 
107  #reduce list to most detailed description only
108  for i, status in enumerate(diagnostics_errors):
109  tmp = diagnostics_errors[:i]+diagnostics_errors[i+1:]
110  if not next((True for status2 in tmp if status2.name.startswith(status.name)), False):
111  diagnostics_errors_detail.append(status)
112 
113  if not diagnostics_errors_detail:
114  if self.em_state > EMState.EM_FREE:
115  self.stop_light()
116  if self.em_state == EMState.EM_BUTTON:
117  self.say(self.sound_em_button_released)
118  elif self.em_state == EMState.EM_BRAKE:
119  self.say(self.sound_em_brake_released)
120  elif self.em_state == EMState.EM_LASER:
121  self.say(self.sound_em_laser_released)
122  elif self.em_state == EMState.EM_WIRELESS:
124  elif self.em_state == EMState.EM_FALL:
125  self.say(self.sound_em_fall_released)
126  elif self.em_state == EMState.EM_INTERNAL:
128  self.em_state = EMState.EM_FREE
129 
130  #determine error state
131  sound_output = ""
132  em_state = EMState.EM_UNKNOWN
133  for status in diagnostics_errors_detail:
134  if "Safety" in status.name:
135  for value in status.values:
136  if (value.key == "button_stop_ok"):
137  if (value.value == "False"):
138  if em_state <= EMState.EM_FREE or em_state > EMState.EM_BUTTON:
139  sound_output = self.sound_em_button_issued
140  em_state = EMState.EM_BUTTON
141  if (value.key == "brake_stop_ok"):
142  if (value.value == "False"):
143  if em_state <= EMState.EM_FREE or em_state > EMState.EM_BRAKE:
144  sound_output = self.sound_em_brake_issued
145  em_state = EMState.EM_BRAKE
146  if (value.key == "laser_stop_ok"):
147  if (value.value == "False"):
148  if em_state <= EMState.EM_FREE or em_state > EMState.EM_LASER:
149  sound_output = self.sound_em_laser_issued
150  em_state = EMState.EM_LASER
151  if (value.key == "wireless_stop_ok"):
152  if (value.value == "False"):
153  if em_state <= EMState.EM_FREE or em_state > EMState.EM_WIRELESS:
154  sound_output = self.sound_em_wireless_issued
155  em_state = EMState.EM_WIRELESS
156  if (value.key == "fall_sensor_front_ok"):
157  if (value.value == "False"):
158  if em_state <= EMState.EM_FREE or self.em_state > EMState.EM_FALL:
159  sound_output = self.sound_em_fall_issued
160  em_state = EMState.EM_FALL
161  if (value.key == "fall_sensor_left_ok"):
162  if (value.value == "False"):
163  if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
164  sound_output = self.sound_em_fall_issued
165  em_state = EMState.EM_FALL
166  if (value.key == "fall_sensor_right_ok"):
167  if (value.value == "False"):
168  if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
169  sound_output = self.sound_em_fall_issued
170  em_state = EMState.EM_FALL
171  if (value.key == "fall_sensors_released"):
172  if (value.value == "False"):
173  if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
174  sound_output = self.sound_em_fall_issued
175  em_state = EMState.EM_FALL
176  if (value.key == "efi_bus_front_io_error"):
177  if (value.value == "True"):
178  if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
179  sound_output = self.sound_em_internal_issued
180  em_state = EMState.EM_INTERNAL
181  if (value.key == "efi_bus_left_io_error"):
182  if (value.value == "True"):
183  if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
184  sound_output = self.sound_em_internal_issued
185  em_state = EMState.EM_INTERNAL
186  if (value.key == "efi_bus_right_io_error"):
187  if (value.value == "True"):
188  if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
189  sound_output = self.sound_em_internal_issued
190  em_state = EMState.EM_INTERNAL
191 
192  rospy.logdebug("self.em_state: %d, em_state: %d"%(self.em_state, em_state))
193  if self.em_state != em_state and em_state > EMState.EM_FREE:
194  #emergency_stop_monitoring has higher priority
195  self.set_light(self.color_error)
196  self.say(sound_output)
197  self.em_state = em_state
198  rospy.logdebug("self.em_state: %d"%(self.em_state))
199 
200  ## Diagnostics monitoring
201  def diagnostics_callback(self, msg):
202  if self.em_state > EMState.EM_FREE:
203  #emergency_stop_monitoring has higher priority
204  return
205 
206  if self.diag_status != msg.level:
207  self.diag_status = msg.level
208  rospy.loginfo("Diagnostics change to "+ str(self.diag_status))
209 
210  if msg.level == DiagnosticStatus.OK:
211  self.stop_light()
212  self.motion_status = -1
213  else: # warning or error
214  self.set_light(self.color_warn)
215 
216  ## Motion Monitoring
217  def jointstate_callback(self, msg):
218  if self.em_state > EMState.EM_FREE:
219  #emergency_stop_monitoring has higher priority
220  return
221  if self.diag_status != DiagnosticStatus.OK:
222  #diagnostics_monitoring has higher priority
223  return
224 
225  threshold = 0.1
226  moving = 0
227  for v in msg.velocity:
228  if abs(v) > threshold:
229  moving = 1
230  break
231 
232  if self.motion_status != moving:
233  self.motion_status = moving
234  rospy.loginfo("Motion change to "+ str(self.motion_status))
235 
236  if moving == 0: # not moving
237  self.stop_light()
238  else: # moving
239  self.set_light(self.color_warn, True)
240 
241 
242  ## set light
243  def set_light(self, color, flashing=False):
244  if self.enable_light:
245  for component in self.light_components:
246  error_code, color_rgba = sss.compose_color(component, color)
247 
248  action_server_name = component + "/set_light"
249  client = actionlib.SimpleActionClient(action_server_name, SetLightModeAction)
250  # trying to connect to server
251  rospy.logdebug("waiting for %s action server to start",action_server_name)
252  if not client.wait_for_server(rospy.Duration(5)):
253  # error: server did not respond
254  rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
255  else:
256  rospy.logdebug("%s action server ready",action_server_name)
257 
258  # sending goal
259  mode = LightMode()
260  mode.priority = 10
261  mode.colors = []
262  mode.colors.append(color_rgba)
263  if flashing:
264  mode.mode = LightModes.FLASH #Flashing
265  mode.frequency = 2.0 #Hz
266  else:
267  mode.mode = LightModes.GLOW #Glow
268  mode.frequency = 10.0 #Hz
269 
270  goal = SetLightModeGoal()
271  goal.mode = mode
272  client.send_goal(goal)
273  client.wait_for_result()
274  result = client.get_result()
275  self.track_id_light = result.track_id
276 
277  self.color = color
278  def stop_light(self):
279  if self.enable_light:
280  if self.track_id_light is not None:
281  for component in self.light_components:
282  srv_server_name = component + "/stop_mode"
283  try:
284  rospy.wait_for_service(srv_server_name, timeout=2)
285  srv_proxy = rospy.ServiceProxy(srv_server_name, StopLightMode)
286  req = StopLightModeRequest()
287  req.track_id = self.track_id_light
288  srv_proxy(req)
289  except Exception as e:
290  rospy.logerr("%s service failed: %s",srv_server_name, e)
291 
292  def say(self, text):
293  if self.enable_sound and text:
294  for component in self.sound_components:
295  sss.say(component, [text])
296 
297 if __name__ == "__main__":
298  rospy.init_node("emergency_stop_monitor")
300  rospy.spin()
def diagnostics_callback(self, msg)
Diagnostics monitoring.
def jointstate_callback(self, msg)
Motion Monitoring.
def set_light(self, color, flashing=False)
set light


cob_monitoring
Author(s): Florian Weisshardt , Felix Messmer
autogenerated on Wed Apr 7 2021 03:03:11