#!/usr/bin/env python # -*- coding: utf-8 -*- ################################################################################ # Copyright 2018 ROBOTIS CO., LTD. # # Licensed under the Apache License, Version 2.0 (the "License"); # you may not use this file except in compliance with the License. # You may obtain a copy of the License at # # http://www.apache.org/licenses/LICENSE-2.0 # # Unless required by applicable law or agreed to in writing, software # distributed under the License is distributed on an "AS IS" BASIS, # WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. # See the License for the specific language governing permissions and # limitations under the License. ################################################################################ # Author: Leon Jung, Gilbert, Ashe Kim import rospy import numpy as np from enum import Enum from std_msgs.msg import UInt8 class CoreModeDecider(): def __init__(self): # subscribes : invoking object detected self.sub_traffic_sign = rospy.Subscriber('/detect/traffic_sign', UInt8, self.cbInvokedByTrafficSign, queue_size=1) self.sub_returned_mode = rospy.Subscriber('/core/returned_mode', UInt8, self.cbReturnedMode, queue_size=1) # publishes : decided mode self.pub_decided_mode = rospy.Publisher('/core/decided_mode', UInt8, queue_size=1) self.InvokedObject = Enum('InvokedObject', 'traffic_sign') self.TrafficSign = Enum('TrafficSign', 'stop') self.CurrentMode = Enum('CurrentMode', 'idle lane_following level_crossing') self.fnInitMode() # Invoke if traffic sign is detected def cbInvokedByTrafficSign(self, traffic_sign_type_msg): rospy.loginfo("invoke sign") self.fnDecideMode(self.InvokedObject.traffic_sign.value, traffic_sign_type_msg) rospy.loginfo("Traffic sign detected") def cbReturnedMode(self, mode): rospy.loginfo("Init Mode") self.fnInitMode() def fnInitMode(self): # starts only when the program is started initially or any mission is completed self.current_mode = self.CurrentMode.lane_following.value self.fnPublishMode() def fnDecideMode(self, invoked_object, msg_data): # starts only when the traffic sign / traffic light is detected & current_mode is lane_following if self.current_mode == self.CurrentMode.lane_following.value: rospy.loginfo("lane_following") if invoked_object == self.InvokedObject.traffic_sign.value: # Any Sign detected rospy.loginfo("traffic sign") if msg_data.data == self.TrafficSign.stop.value: # Stop Sign detected self.current_mode = self.CurrentMode.level_crossing.value rospy.loginfo("level crossing") else: pass self.fnPublishMode() else: pass def fnPublishMode(self): decided_mode = UInt8() decided_mode.data = self.current_mode self.pub_decided_mode.publish(decided_mode) def main(self): rospy.spin() if __name__ == '__main__': rospy.init_node('core_mode_decider') node = CoreModeDecider() node.main()