21 from cob_msgs.msg
import EmergencyStopState
23 from simple_script_server
import *
32 rospy.Subscriber(
"/emergency_stop_state", EmergencyStopState, self.
em_cb, queue_size=1)
35 for component
in list(self.components.keys()):
36 rospy.loginfo(
"[auto_init]: Waiting for %s to start...", component)
37 rospy.wait_for_service(
"/" + component +
"/driver/init")
40 while not rospy.is_shutdown():
42 rospy.loginfo(
"[auto_init]: Waiting for emergency stop to be released...")
45 except rospy.exceptions.ROSInterruptException
as e:
49 rospy.loginfo(
"[auto_init]: Initializing components")
50 for component
in list(self.components.keys()):
52 while not rospy.is_shutdown():
54 rospy.logerr(
"[auto_init]: Could not initialize %s after %s retries", component, str(retries))
57 handle = sss.init(component)
58 if not (handle.get_error_code() == 0):
59 rospy.logerr(
"[auto_init]: Could not initialize %s. Retrying...(%s of %s)", component, str(retries), str(self.
max_retries))
61 rospy.loginfo(
"[auto_init]: Component %s initialized successfully", component)
68 if __name__ ==
"__main__":
69 rospy.init_node(
"auto_init")
70 rospy.loginfo(
"auto init running")
72 rospy.loginfo(
"auto init finished")