00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 import sys
00019 import copy
00020 from enum import IntEnum
00021
00022 import rospy
00023 from sensor_msgs.msg import JointState
00024 from diagnostic_msgs.msg import DiagnosticStatus, DiagnosticArray
00025
00026 from cob_msgs.msg import *
00027 from cob_light.msg import LightMode, LightModes, SetLightModeGoal, SetLightModeAction
00028 from cob_light.srv import StopLightMode, StopLightModeRequest
00029
00030 from simple_script_server import *
00031 sss = simple_script_server()
00032
00033 class EMState(IntEnum):
00034 EM_UNKNOWN = -1
00035 EM_FREE = 0
00036 EM_BUTTON = 1
00037 EM_BRAKE = 2
00038 EM_LASER = 3
00039 EM_WIRELESS = 4
00040 EM_FALL = 5
00041 EM_INTERNAL = 6
00042
00043
00044 class emergency_stop_monitor():
00045 def __init__(self):
00046 self.color = "None"
00047 self.enable_sound = rospy.get_param("~enable_sound", False)
00048 self.enable_light = rospy.get_param("~enable_light", False)
00049 self.diagnostics_based = rospy.get_param("~diagnostics_based", False)
00050 self.motion_based = rospy.get_param("~motion_based", False)
00051 self.track_id_light = None
00052
00053 if(self.enable_light):
00054 if not rospy.has_param("~light_components"):
00055 rospy.logwarn("parameter light_components does not exist on ROS Parameter Server, aborting...")
00056 sys.exit(1)
00057 self.light_components = rospy.get_param("~light_components")
00058
00059
00060 self.color_error = rospy.get_param("~color_error","red")
00061 self.color_warn = rospy.get_param("~color_warn","yellow")
00062 self.color_ok = rospy.get_param("~color_ok","green")
00063 self.color_off = rospy.get_param("~color_off","black")
00064
00065 if(self.enable_sound):
00066 if not rospy.has_param("~sound_components"):
00067 rospy.logwarn("parameter sound_components does not exist on ROS Parameter Server, aborting...")
00068 sys.exit(1)
00069 self.sound_components = rospy.get_param("~sound_components")
00070
00071 self.sound_em_button_released = rospy.get_param("~sound_em_button_released", "button released")
00072 self.sound_em_button_issued = rospy.get_param("~sound_em_button_issued", "button issued")
00073 self.sound_em_brake_released = rospy.get_param("~sound_em_brake_released", "brake released")
00074 self.sound_em_brake_issued = rospy.get_param("~sound_em_brake_issued", "brake issued")
00075 self.sound_em_laser_released = rospy.get_param("~sound_em_laser_released", "laser released")
00076 self.sound_em_laser_issued = rospy.get_param("~sound_em_laser_issued", "laser issued")
00077 self.sound_em_wireless_released = rospy.get_param("~sound_em_wireless_released", "wireless released")
00078 self.sound_em_wireless_issued = rospy.get_param("~sound_em_wireless_issued", "wireless issued")
00079 self.sound_em_fall_released = rospy.get_param("~sound_em_fall_released", "fall released")
00080 self.sound_em_fall_issued = rospy.get_param("~sound_em_fall_issued", "fall issued")
00081 self.sound_em_internal_released = rospy.get_param("~sound_em_internal_released", "internal released")
00082 self.sound_em_internal_issued = rospy.get_param("~sound_em_internal_issued", "internal issued")
00083
00084 rospy.Subscriber("/diagnostics_agg", DiagnosticArray, self.diagnostics_agg_callback, queue_size=1)
00085 self.em_state = EMState.EM_UNKNOWN
00086
00087 self.diag_status = -1
00088 if(self.diagnostics_based):
00089 rospy.Subscriber("/diagnostics_toplevel_state", DiagnosticStatus, self.diagnostics_callback, queue_size=1)
00090 self.last_diag = rospy.get_rostime()
00091
00092 self.motion_status = -1
00093 if(self.motion_based):
00094 rospy.Subscriber("/joint_states", JointState, self.jointstate_callback, queue_size=1)
00095 self.last_vel = rospy.get_rostime()
00096
00097 def diagnostics_agg_callback(self, msg):
00098 diagnostics_errors = []
00099 diagnostics_errors_detail = []
00100
00101
00102 for status in msg.status:
00103 if "Safety" in status.name:
00104 if status.level > DiagnosticStatus.OK:
00105 diagnostics_errors.append(status)
00106
00107
00108 for i, status in enumerate(diagnostics_errors):
00109 tmp = diagnostics_errors[:i]+diagnostics_errors[i+1:]
00110 if not next((True for status2 in tmp if status2.name.startswith(status.name)), False):
00111 diagnostics_errors_detail.append(status)
00112
00113 if not diagnostics_errors_detail:
00114 if self.em_state > EMState.EM_FREE:
00115 self.stop_light()
00116 if self.em_state == EMState.EM_BUTTON:
00117 self.say(self.sound_em_button_released)
00118 elif self.em_state == EMState.EM_BRAKE:
00119 self.say(self.sound_em_brake_released)
00120 elif self.em_state == EMState.EM_LASER:
00121 self.say(self.sound_em_laser_released)
00122 elif self.em_state == EMState.EM_WIRELESS:
00123 self.say(self.sound_em_wireless_released)
00124 elif self.em_state == EMState.EM_FALL:
00125 self.say(self.sound_em_fall_released)
00126 elif self.em_state == EMState.EM_INTERNAL:
00127 self.say(self.sound_em_internal_released)
00128 self.em_state = EMState.EM_FREE
00129
00130
00131 sound_output = ""
00132 em_state = EMState.EM_UNKNOWN
00133 for status in diagnostics_errors_detail:
00134 if "Safety" in status.name:
00135 for value in status.values:
00136 if (value.key == "button_stop_ok"):
00137 if (value.value == "False"):
00138 if em_state <= EMState.EM_FREE or em_state > EMState.EM_BUTTON:
00139 sound_output = self.sound_em_button_issued
00140 em_state = EMState.EM_BUTTON
00141 if (value.key == "brake_stop_ok"):
00142 if (value.value == "False"):
00143 if em_state <= EMState.EM_FREE or em_state > EMState.EM_BRAKE:
00144 sound_output = self.sound_em_brake_issued
00145 em_state = EMState.EM_BRAKE
00146 if (value.key == "laser_stop_ok"):
00147 if (value.value == "False"):
00148 if em_state <= EMState.EM_FREE or em_state > EMState.EM_LASER:
00149 sound_output = self.sound_em_laser_issued
00150 em_state = EMState.EM_LASER
00151 if (value.key == "wireless_stop_ok"):
00152 if (value.value == "False"):
00153 if em_state <= EMState.EM_FREE or em_state > EMState.EM_WIRELESS:
00154 sound_output = self.sound_em_wireless_issued
00155 em_state = EMState.EM_WIRELESS
00156 if (value.key == "fall_sensor_front_ok"):
00157 if (value.value == "False"):
00158 if em_state <= EMState.EM_FREE or self.em_state > EMState.EM_FALL:
00159 sound_output = self.sound_em_fall_issued
00160 em_state = EMState.EM_FALL
00161 if (value.key == "fall_sensor_left_ok"):
00162 if (value.value == "False"):
00163 if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
00164 sound_output = self.sound_em_fall_issued
00165 em_state = EMState.EM_FALL
00166 if (value.key == "fall_sensor_right_ok"):
00167 if (value.value == "False"):
00168 if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
00169 sound_output = self.sound_em_fall_issued
00170 em_state = EMState.EM_FALL
00171 if (value.key == "fall_sensors_released"):
00172 if (value.value == "False"):
00173 if em_state <= EMState.EM_FREE or em_state > EMState.EM_FALL:
00174 sound_output = self.sound_em_fall_issued
00175 em_state = EMState.EM_FALL
00176 if (value.key == "efi_bus_front_io_error"):
00177 if (value.value == "True"):
00178 if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
00179 sound_output = self.sound_em_internal_issued
00180 em_state = EMState.EM_INTERNAL
00181 if (value.key == "efi_bus_left_io_error"):
00182 if (value.value == "True"):
00183 if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
00184 sound_output = self.sound_em_internal_issued
00185 em_state = EMState.EM_INTERNAL
00186 if (value.key == "efi_bus_right_io_error"):
00187 if (value.value == "True"):
00188 if em_state <= EMState.EM_FREE or em_state > EMState.EM_INTERNAL:
00189 sound_output = self.sound_em_internal_issued
00190 em_state = EMState.EM_INTERNAL
00191
00192 rospy.logdebug("self.em_state: %d, em_state: %d"%(self.em_state, em_state))
00193 if self.em_state != em_state and em_state > EMState.EM_FREE:
00194
00195 self.set_light(self.color_error)
00196 self.say(sound_output)
00197 self.em_state = em_state
00198 rospy.logdebug("self.em_state: %d"%(self.em_state))
00199
00200
00201 def diagnostics_callback(self, msg):
00202 if self.em_state > EMState.EM_FREE:
00203
00204 return
00205
00206 if self.diag_status != msg.level:
00207 self.diag_status = msg.level
00208 rospy.loginfo("Diagnostics change to "+ str(self.diag_status))
00209
00210 if msg.level == DiagnosticStatus.OK:
00211 self.stop_light()
00212 self.motion_status = -1
00213 else:
00214 self.set_light(self.color_warn)
00215
00216
00217 def jointstate_callback(self, msg):
00218 if self.em_state > EMState.EM_FREE:
00219
00220 return
00221 if self.diag_status != DiagnosticStatus.OK:
00222
00223 return
00224
00225 threshold = 0.1
00226 moving = 0
00227 for v in msg.velocity:
00228 if abs(v) > threshold:
00229 moving = 1
00230 break
00231
00232 if self.motion_status != moving:
00233 self.motion_status = moving
00234 rospy.loginfo("Motion change to "+ str(self.motion_status))
00235
00236 if moving == 0:
00237 self.stop_light()
00238 else:
00239 self.set_light(self.color_warn, True)
00240
00241
00242
00243 def set_light(self, color, flashing=False):
00244 if self.enable_light:
00245 for component in self.light_components:
00246 error_code, color_rgba = sss.compose_color(component, color)
00247
00248 action_server_name = component + "/set_light"
00249 client = actionlib.SimpleActionClient(action_server_name, SetLightModeAction)
00250
00251 rospy.logdebug("waiting for %s action server to start",action_server_name)
00252 if not client.wait_for_server(rospy.Duration(5)):
00253
00254 rospy.logerr("%s action server not ready within timeout, aborting...", action_server_name)
00255 else:
00256 rospy.logdebug("%s action server ready",action_server_name)
00257
00258
00259 mode = LightMode()
00260 mode.priority = 10
00261 mode.colors = []
00262 mode.colors.append(color_rgba)
00263 if flashing:
00264 mode.mode = LightModes.FLASH
00265 mode.frequency = 2.0
00266 else:
00267 mode.mode = LightModes.GLOW
00268 mode.frequency = 10.0
00269
00270 goal = SetLightModeGoal()
00271 goal.mode = mode
00272 client.send_goal(goal)
00273 client.wait_for_result()
00274 result = client.get_result()
00275 self.track_id_light = result.track_id
00276
00277 self.color = color
00278 def stop_light(self):
00279 if self.enable_light:
00280 if self.track_id_light is not None:
00281 for component in self.light_components:
00282 srv_server_name = component + "/stop_mode"
00283 try:
00284 rospy.wait_for_service(srv_server_name, timeout=2)
00285 srv_proxy = rospy.ServiceProxy(srv_server_name, StopLightMode)
00286 req = StopLightModeRequest()
00287 req.track_id = self.track_id_light
00288 srv_proxy(req)
00289 except Exception as e:
00290 rospy.logerr("%s service failed: %s",srv_server_name, e)
00291
00292 def say(self, text):
00293 if self.enable_sound and text:
00294 for component in self.sound_components:
00295 sss.say(component, [text])
00296
00297 if __name__ == "__main__":
00298 rospy.init_node("emergency_stop_monitor")
00299 emergency_stop_monitor()
00300 rospy.spin()