20 from enum
import IntEnum
23 from std_msgs.msg
import Empty
24 from sensor_msgs.msg
import JointState
25 from diagnostic_msgs.msg
import DiagnosticStatus, DiagnosticArray
28 from cob_light.msg
import LightMode, LightModes, SetLightModeGoal, SetLightModeAction
29 from cob_light.srv
import StopLightMode, StopLightModeRequest
31 from simple_script_server
import *
56 if not rospy.has_param(
"~light_components"):
57 rospy.logwarn(
"parameter light_components does not exist on ROS Parameter Server, aborting...")
63 self.
color_warn = rospy.get_param(
"~color_warn",
"yellow")
64 self.
color_ok = rospy.get_param(
"~color_ok",
"green")
65 self.
color_off = rospy.get_param(
"~color_off",
"black")
68 if not rospy.has_param(
"~sound_components"):
69 rospy.logwarn(
"parameter sound_components does not exist on ROS Parameter Server, aborting...")
96 rospy.Subscriber(
"/diagnostics_toplevel_state", DiagnosticStatus, self.
diagnostics_callback, queue_size=1)
105 emergency_stop_topic = rospy.get_param(
"~emergency_stop_topic",
"/emergency_stop_state")
117 diagnostics_errors = []
118 diagnostics_errors_detail = []
121 for status
in msg.status:
122 if "Safety" in status.name:
123 if status.level > DiagnosticStatus.WARN:
124 diagnostics_errors.append(status)
127 for i, status
in enumerate(diagnostics_errors):
128 tmp = diagnostics_errors[:i]+diagnostics_errors[i+1:]
129 if not next((
True for status2
in tmp
if status2.name.startswith(status.name)),
False):
130 diagnostics_errors_detail.append(status)
132 if not diagnostics_errors_detail:
135 if self.
em_state == EMState.EM_BUTTON:
138 elif self.
em_state == EMState.EM_BRAKE:
141 elif self.
em_state == EMState.EM_LASER:
144 elif self.
em_state == EMState.EM_WIRELESS:
147 elif self.
em_state == EMState.EM_FALL:
150 elif self.
em_state == EMState.EM_INTERNAL:
157 em_state = EMState.EM_UNKNOWN
158 for status
in diagnostics_errors_detail:
159 if "Safety" in status.name:
160 for value
in status.values:
161 if (value.key ==
"button_stop_ok"):
162 if (value.value ==
"False"):
163 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_BUTTON:
165 em_state = EMState.EM_BUTTON
166 if (value.key ==
"brake_stop_ok"):
167 if (value.value ==
"False"):
168 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_BRAKE:
170 em_state = EMState.EM_BRAKE
171 if (value.key ==
"laser_stop_ok"):
172 if (value.value ==
"False"):
173 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_LASER:
175 em_state = EMState.EM_LASER
176 if (value.key ==
"wireless_stop_ok"):
177 if (value.value ==
"False"):
178 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_WIRELESS:
180 em_state = EMState.EM_WIRELESS
181 if (value.key ==
"fall_sensor_front_ok"):
182 if (value.value ==
"False"):
183 if em_state <= EMState.EM_FREE
or self.
em_state > EMState.EM_FALL:
185 em_state = EMState.EM_FALL
186 if (value.key ==
"fall_sensor_left_ok"):
187 if (value.value ==
"False"):
188 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_FALL:
190 em_state = EMState.EM_FALL
191 if (value.key ==
"fall_sensor_right_ok"):
192 if (value.value ==
"False"):
193 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_FALL:
195 em_state = EMState.EM_FALL
196 if (value.key ==
"fall_sensors_released"):
197 if (value.value ==
"False"):
198 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_FALL:
200 em_state = EMState.EM_FALL
201 if (value.key ==
"efi_bus_front_io_error"):
202 if (value.value ==
"True"):
203 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_INTERNAL:
205 em_state = EMState.EM_INTERNAL
206 if (value.key ==
"efi_bus_left_io_error"):
207 if (value.value ==
"True"):
208 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_INTERNAL:
210 em_state = EMState.EM_INTERNAL
211 if (value.key ==
"efi_bus_right_io_error"):
212 if (value.value ==
"True"):
213 if em_state <= EMState.EM_FREE
or em_state > EMState.EM_INTERNAL:
215 em_state = EMState.EM_INTERNAL
217 rospy.logdebug(
"self.em_state: %d, em_state: %d"%(self.
em_state, em_state))
218 if self.
em_state != em_state
and em_state > EMState.EM_FREE:
221 self.
say(sound_output)
223 rospy.logdebug(
"self.em_state: %d"%(self.
em_state))
233 rospy.loginfo(
"Diagnostics change to "+ str(self.
diag_status))
235 if msg.level == DiagnosticStatus.OK:
252 for v
in msg.velocity:
253 if abs(v) > threshold:
268 if msg.emergency_state == EmergencyStopState.EMSTOP:
270 if msg.emergency_button_stop:
272 rospy.logwarn(
"Emergency stop button has been issued!")
273 elif msg.scanner_stop:
275 rospy.logwarn(
"Scanner stop has been issued!")
281 if msg.emergency_state == EmergencyStopState.EMFREE:
283 rospy.loginfo(
"Emergency stop released")
293 error_code, color_rgba = sss.compose_color(component, color)
295 action_server_name = component +
"/set_light"
298 rospy.logdebug(
"waiting for %s action server to start",action_server_name)
299 if not client.wait_for_server(rospy.Duration(5)):
301 rospy.logerr(
"%s action server not ready within timeout, aborting...", action_server_name)
303 rospy.logdebug(
"%s action server ready",action_server_name)
309 mode.colors.append(color_rgba)
311 mode.mode = LightModes.FLASH
314 mode.mode = LightModes.GLOW
315 mode.frequency = 10.0
317 goal = SetLightModeGoal()
319 client.send_goal(goal)
320 client.wait_for_result()
321 result = client.get_result()
329 srv_server_name = component +
"/stop_mode"
331 rospy.wait_for_service(srv_server_name, timeout=2)
332 srv_proxy = rospy.ServiceProxy(srv_server_name, StopLightMode)
333 req = StopLightModeRequest()
336 except Exception
as e:
337 rospy.logerr(
"%s service failed: %s",srv_server_name, e)
342 sss.say(component, [text])
344 if __name__ ==
"__main__":
345 rospy.init_node(
"emergency_stop_monitor")