Newer
Older
turtlebot3_noetic / src / turtlebot3_autorace_2020 / turtlebot3_autorace_core / nodes / core_node_controller
#!/usr/bin/env python
# -*- coding: utf-8 -*-
import rospy, roslaunch
import numpy as np
import subprocess
import os
import sys
from enum import Enum
from std_msgs.msg import UInt8
class CoreNodeController():
 def __init__(self):
  self.ros_package_path = os.path.dirname(os.path.realpath(__file__))
  self.ros_package_path = self.ros_package_path.replace('turtlebot3_autorace_core/nodes', '')
  self.sub_mode_control = rospy.Subscriber('/core/decided_mode', UInt8, self.cbReceiveMode, queue_size=1)
  self.traffic_light = rospy.Subscriber('/detect/traffic_light',UInt8,self.cbTrafficLight, queue_size=1)
  self.CurrentMode = Enum('CurrentMode', 'idle lane_following traffic_light parking_lot level_crossing tunnel intersection construction')
  self.sub_intersection_stamped = rospy.Subscriber('/detect/intersection_stamped', UInt8, self.cbIntersectionStamped, queue_size=1)
  self.sub_construction_stamped = rospy.Subscriber('/detect/construction_stamped', UInt8, self.cbConstructionStamped, queue_size=1)
  self.sub_parking_lot_stamped = rospy.Subscriber('/detect/parking_lot_stamped', UInt8, self.cbParkingLotStamped, queue_size=1)
  self.sub_level_crossing_stamped = rospy.Subscriber('/detect/level_crossing_stamped', UInt8, self.cbLevelCrossingStamped, queue_size=1)
  self.sub_tunnel_stamped = rospy.Subscriber('/detect/tunnel_stamped', UInt8, self.cbTunnelStamped, queue_size=1)
  self.pub_traffic_light_order = rospy.Publisher('/detect/traffic_light_order', UInt8, queue_size=1)
  self.pub_intersection_order = rospy.Publisher('/detect/intersection_order', UInt8, queue_size=1)
  self.pub_construction_order = rospy.Publisher('/detect/construction_order', UInt8, queue_size=1)
  self.pub_parking_lot_order = rospy.Publisher('/detect/parking_lot_order', UInt8, queue_size=1)
  self.pub_level_crossing_order = rospy.Publisher('/detect/level_crossing_order', UInt8, queue_size=1)
  self.pub_tunnel_order = rospy.Publisher('/detect/tunnel_order', UInt8, queue_size=1)
  self.pub_mode_return = rospy.Publisher('/core/returned_mode', UInt8, queue_size=1)
  self.StepOfIntersection = Enum('StepOfIntersection', 'searching_intersection_sign searching_parking_point_line searching_nonreserved_parking_area parking')
  self.StepOfConstruction = Enum('StepOfConstruction', 'searching_construction_sign searching_parking_point_line searching_nonreserved_parking_area parking')
  self.StepOfParkingLot = Enum('StepOfParkingLot', 'searching_parking_sign searching_parking_point_line searching_nonreserved_parking_area parking')
  self.StepOfLevelCrossing = Enum('StepOfLevelCrossing', 'searching_stop_sign searching_level_crossing watching_level_crossing stop pass_level_crossing')
  self.StepOfTunnel = Enum('StepOfTunnel', 'searching_tunnel_sign go_in_to_tunnel navigation go_out_from_tunnel exit')
  self.current_step_parking_lot = self.StepOfParkingLot.searching_parking_sign.value
  self.current_step_level_crossing = self.StepOfLevelCrossing.searching_stop_sign.value
  self.current_step_tunnel = self.StepOfTunnel.searching_tunnel_sign.value
  self.Launcher = Enum('Launcher', 'launch_camera_ex_calib launch_detect_sign launch_detect_lane launch_control_lane launch_detect_traffic_light launch_control_traffic_light launch_detect_parking launch_control_parking launch_detect_level_crossing launch_control_level_crossing launch_detect_tunnel launch_control_tunnel detect_intersection detect_construction')
  self.uuid = roslaunch.rlutil.get_or_generate_uuid(None, False)
  self.launch_camera_launched = False
  self.launch_detect_sign_launched = False
  self.launch_detect_lane_launched = False 
  self.launch_control_lane_launched = False
  self.launch_detect_parking_launched = False
  self.launch_control_parking_launched = False
  self.launch_detect_level_crossing_launched = False
  self.launch_detect_traffic_light_launched = False
  self.launch_detect_tunnel_launched = False
  self.launch_control_tunnel_launched = False
  self.launch_detect_intersection_launched = False
  self.launch_detect_construction_launched = False
  self.current_mode = self.CurrentMode.idle.value
  self.is_triggered = False
  self.is_go = False
  loop_rate = rospy.Rate(10) # 10hz
  while not rospy.is_shutdown():
   if self.is_triggered == True:
    self.fnControlNode()
   loop_rate.sleep()
 def cbReceiveMode(self, mode_msg):
  rospy.loginfo("starts the progress with %d", mode_msg.data)
  self.current_mode = mode_msg.data
  self.is_triggered = True
 def cbTrafficLight(self, mode_msg):
  self.is_go = True 
 def cbParkingLotStamped(self, parking_lot_msg):
  rospy.loginfo("ParkingLot Step changed from %d", self.current_step_parking_lot)
  self.current_step_parking_lot = parking_lot_msg.data
  rospy.loginfo("into %d", self.current_step_parking_lot)
  if self.current_step_parking_lot == self.StepOfParkingLot.parking.value:
   self.current_mode = self.CurrentMode.lane_following.value
   msg_mode_return = UInt8()
   msg_mode_return.data = self.current_mode
   self.current_step_parking_lot = self.StepOfParkingLot.searching_parking_sign.value
   rospy.loginfo("pub_mode_return")
   self.pub_mode_return.publish(msg_mode_return)
  self.is_triggered = True
 def cbIntersectionStamped(self, intersection_msg):
  rospy.loginfo("Intersection Step changed from %d", self.current_step_intersection)
  self.current_step_intersection = intersection_msg.data
  rospy.loginfo("into %d", self.current_step_intersection)
  if self.current_step_intersection == self.StepOfIntersection.intersection.value:
   self.current_mode = self.CurrentMode.lane_following.value
   msg_mode_return = UInt8()
   msg_mode_return.data = self.current_mode
   self.current_step_intersection = self.StepOfParkingLot.searching_intersection_sign.value
   rospy.loginfo("pub_mode_return")
   self.pub_mode_return.publish(msg_mode_return)
  self.is_triggered = True
 def cbConstructionStamped(self, construction_msg):
  rospy.loginfo("Construction Step changed from %d", self.current_step_construction)
  self.current_step_construction = construction_msg.data
  rospy.loginfo("into %d", self.current_step_construction)
  if self.current_step_construction == self.StepOfConstruction.construction.value:
   self.current_mode = self.CurrentMode.lane_following.value
   msg_mode_return = UInt8()
   msg_mode_return.data = self.current_mode
   self.current_step_construction = self.StepOfConstruction.searching_construction_sign.value
   rospy.loginfo("pub_mode_return")
   self.pub_mode_return.publish(msg_mode_return)
  self.is_triggered = True
 def cbLevelCrossingStamped(self, level_crossing_msg):
  rospy.loginfo("LevelCrossing Step changed from %d", self.current_step_level_crossing)
  self.current_step_level_crossing = level_crossing_msg.data
  rospy.loginfo("into %d", self.current_step_level_crossing)
  if self.current_step_level_crossing == self.StepOfLevelCrossing.pass_level_crossing.value:
   self.current_mode = self.CurrentMode.level_crossing.value
   msg_mode_return = UInt8()
   msg_mode_return.data = self.current_mode
   self.pub_mode_return.publish(msg_mode_return)
  self.is_triggered = True
 def cbTunnelStamped(self, tunnel_msg):
  rospy.loginfo("Tunnel Step changed from %d", self.current_step_tunnel)
  self.current_step_tunnel = tunnel_msg.data
  rospy.loginfo("into %d", self.current_step_tunnel)
  if self.current_step_tunnel == self.StepOfTunnel.searching_tunnel_sign.value:
   self.current_mode = self.CurrentMode.tunnel.value
   msg_mode_return = UInt8()
   msg_mode_return.data = self.current_mode
   self.pub_mode_return.publish(msg_mode_return)
  self.is_triggered = True
 def fnControlNode(self):
  if self.current_mode == self.CurrentMode.lane_following.value:
   rospy.loginfo("New trigger for lane_following")
   self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, True)
   self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
   self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
   self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, True)
   self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
   self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
   self.fnLaunch(self.Launcher.launch_detect_parking.value, False)
   self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
   self.fnLaunch(self.Launcher.launch_detect_tunnel.value, False)
   self.fnLaunch(self.Launcher.launch_control_lane.value, True)
   self.fnLaunch(self.Launcher.launch_control_parking.value, False)
   self.fnLaunch(self.Launcher.launch_control_tunnel.value, False)
  elif self.current_mode == self.CurrentMode.traffic_light.value:
   rospy.loginfo("New trigger for traffic_light")
   msg_pub_traffic_light_order = UInt8()
   if self.current_step_traffic_light == self.StepOfTrafficLight.searching_traffic_light.value:
    rospy.loginfo("Current step : searching_traffic_light")
    rospy.loginfo("Go to next step : in_traffic_light")
    msg_pub_traffic_light_order.data = self.StepOfTrafficLight.in_traffic_light.value
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, False)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_control_parking.value, False)
    self.fnLaunch(self.Launcher.launch_control_level_crossing.value, False)
   elif self.current_step_traffic_light == self.StepOfTrafficLight.in_traffic_light.value:
    rospy.loginfo("Current step : in_traffic_light")
    rospy.loginfo("Go to next step : pass_traffic_light")
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, False)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_control_parking.value, False)
    self.fnLaunch(self.Launcher.launch_control_level_crossing.value, False)
   rospy.sleep(2)
   self.pub_traffic_light_order.publish(msg_pub_traffic_light_order)
  elif self.current_mode == self.CurrentMode.parking_lot.value:
   rospy.loginfo("New trigger for parking_lot")
   msg_pub_parking_lot_order = UInt8()
   if self.current_step_parking_lot == self.StepOfParkingLot.searching_parking_sign.value:
    rospy.loginfo("Current step : searching_parking_sign")
    rospy.loginfo("Go to next step : searching_parking_point_line")
    msg_pub_parking_lot_order.data = self.StepOfParkingLot.searching_parking_point_line.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_control_parking.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_parking_lot == self.StepOfParkingLot.searching_parking_point_line.value:
    rospy.loginfo("Current step : searching_parking_point_line")
    rospy.loginfo("Go to next step : searching_nonreserved_parking_area")
    msg_pub_parking_lot_order.data = self.StepOfParkingLot.searching_nonreserved_parking_area.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_control_parking.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_parking_lot == self.StepOfParkingLot.searching_nonreserved_parking_area.value:
    rospy.loginfo("Current step : searching_nonreserved_parking_area")
    rospy.loginfo("Go to next step : parking")
    msg_pub_parking_lot_order.data = self.StepOfParkingLot.parking.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, False)
    self.fnLaunch(self.Launcher.launch_control_parking.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_parking_lot == self.StepOfParkingLot.parking.value:
    rospy.loginfo("Current step : parking")
    rospy.loginfo("Go to next step : searching_parking_sign")
    msg_pub_parking_lot_order.data = self.StepOfParkingLot.searching_parking_sign.value
    self.fnLaunch(self.Launcher.launch_control_parking.value, False)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_parking.value, False)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   rospy.sleep(2)
   self.pub_parking_lot_order.publish(msg_pub_parking_lot_order)
  elif self.current_mode == self.CurrentMode.level_crossing.value:
   rospy.loginfo("New trigger for level_crossing")
   msg_pub_level_crossing_order = UInt8()
   if self.current_step_level_crossing == self.StepOfLevelCrossing.searching_stop_sign.value:
    rospy.loginfo("Current step : searching_stop_sign")
    rospy.loginfo("Go to next step : searching_level_crossing")
    msg_pub_level_crossing_order.data = self.StepOfLevelCrossing.searching_level_crossing.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_level_crossing == self.StepOfLevelCrossing.searching_level_crossing.value:
    rospy.loginfo("Current step : searching_level_crossing")
    rospy.loginfo("Go to next step : watching_level_crossing")
    msg_pub_level_crossing_order.data = self.StepOfLevelCrossing.watching_level_crossing.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_level_crossing == self.StepOfLevelCrossing.watching_level_crossing.value:
    rospy.loginfo("Current step : watching_level_crossing")
    rospy.loginfo("Go to next step : stop")
    msg_pub_level_crossing_order.data = self.StepOfLevelCrossing.stop.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_level_crossing == self.StepOfLevelCrossing.stop.value:
    rospy.loginfo("Current step : stop")
    rospy.loginfo("Go to next step : pass_level_crossing")
    msg_pub_level_crossing_order.data = self.StepOfLevelCrossing.pass_level_crossing.value
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   elif self.current_step_level_crossing == self.StepOfLevelCrossing.pass_level_crossing.value:
    rospy.loginfo("Current step : pass_level_crossing")
    rospy.loginfo("Go to next step : searching_stop_sign")
    msg_pub_level_crossing_order.data = self.StepOfLevelCrossing.searching_stop_sign.value
    self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
   rospy.sleep(2)
   self.pub_level_crossing_order.publish(msg_pub_level_crossing_order)
  elif self.current_mode == self.CurrentMode.tunnel.value:
   rospy.loginfo("New trigger for tunnel")
   msg_pub_tunnel_order = UInt8()
   if self.current_step_tunnel == self.StepOfTunnel.searching_tunnel_sign.value:
    rospy.loginfo("Current step : searching_tunnel_sign")
    rospy.loginfo("Go to next step : go_in_to_tunnel")
    msg_pub_tunnel_order.data = self.StepOfTunnel.go_in_to_tunnel.value
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, True)
    self.fnLaunch(self.Launcher.launch_control_lane.value, False)
    self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, False)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
    self.fnLaunch(self.Launcher.launch_control_tunnel.value, False)
   elif self.current_step_tunnel == self.StepOfTunnel.go_in_to_tunnel.value:
    rospy.loginfo("Current step : go_in_to_tunnel")
    rospy.loginfo("Go to next step : navigation")
    msg_pub_tunnel_order.data = self.StepOfTunnel.navigation.value
    self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, False)
    self.fnLaunch(self.Launcher.launch_control_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, True)
    self.fnLaunch(self.Launcher.launch_control_tunnel.value, True)
   elif self.current_step_tunnel == self.StepOfTunnel.navigation.value:
    rospy.loginfo("Current step : navigation")
    rospy.loginfo("Go to next step : go_out_from_tunnel")
    msg_pub_tunnel_order.data = self.StepOfTunnel.go_out_from_tunnel.value
    self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, True)
    self.fnLaunch(self.Launcher.launch_control_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, False)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, False)
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, True)
    self.fnLaunch(self.Launcher.launch_control_tunnel.value, False)
   elif self.current_step_tunnel == self.StepOfTunnel.go_out_from_tunnel.value:
    rospy.loginfo("Current step : go_out_from_tunnel")
    rospy.loginfo("Go to next step : exit")
    msg_pub_tunnel_order.data = self.StepOfTunnel.exit.value
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, False)
    self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, True)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_control_tunnel.value, False)
   elif self.current_step_tunnel == self.StepOfTunnel.exit.value:
    rospy.loginfo("Current step : exit")
    rospy.loginfo("Go to next step : searching_tunnel_sign")
    msg_pub_tunnel_order.data = self.StepOfTunnel.searching_tunnel_sign.value
    self.fnLaunch(self.Launcher.launch_detect_tunnel.value, False)
    self.fnLaunch(self.Launcher.launch_camera_ex_calib.value, True)
    self.fnLaunch(self.Launcher.launch_detect_intersection.value, False)
    self.fnLaunch(self.Launcher.launch_detect_construction.value, False)
    self.fnLaunch(self.Launcher.launch_detect_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_sign.value, True)
    self.fnLaunch(self.Launcher.launch_detect_traffic_light.value, True)
    self.fnLaunch(self.Launcher.launch_control_lane.value, True)
    self.fnLaunch(self.Launcher.launch_detect_level_crossing.value, False)
    self.fnLaunch(self.Launcher.launch_control_tunnel.value, False)
   rospy.sleep(2)
   self.pub_tunnel_order.publish(msg_pub_tunnel_order)
  self.is_triggered = False
 def fnLaunch(self, launch_num, is_start):
  if launch_num == self.Launcher.launch_camera_ex_calib.value:
   if is_start == True:
    if self.launch_camera_launched == False:
     self.launch_camera = roslaunch.scriptapi.ROSLaunch()
     self.launch_camera = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_camera/launch/turtlebot3_autorace_extrinsic_camera_calibration.launch"])
     self.launch_camera_launched = True
     self.launch_camera.start()
    else:
     pass
   else:
    if self.launch_camera_launched == True:
     self.launch_camera_launched = False
     self.launch_camera.shutdown()
    else:
     pass
  elif launch_num == self.Launcher.launch_construction.value:
   if is_start == True:
    if self.launch_detect_sign_launched == False:
     self.launch_detect_sign = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_sign = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_construction.launch"])
     self.launch_detect_sign_launched = True
     self.launch_detect_sign.start()
    else:
     pass
   else:
    if self.launch_detect_sign_launched == True:
     self.launch_detect_sign_launched = False
     self.launch_detect_sign.shutdown()
    else:
     pass
  elif launch_num == self.Launcher.launch_detect_intersection.value:
   if is_start == True:
    if self.launch_detect_sign_launched == False:
     self.launch_detect_sign = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_sign = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_intersection.launch"])
     self.launch_detect_sign_launched = True
     self.launch_detect_sign.start()
    else:
     pass
   else:
    if self.launch_detect_sign_launched == True:
     self.launch_detect_sign_launched = False
     self.launch_detect_sign.shutdown()
    else:
     pass
   elif launch_num == self.Launcher.launch_detect_traffic_light.value:
   if is_start == True:
    if self.launch_detect_sign_launched == False:
     self.launch_detect_sign = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_sign = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_traffic_light.launch"])
     self.launch_detect_sign_launched = True
     self.launch_detect_sign.start()
    else:
     pass
   else:
    if self.launch_detect_sign_launched == True:
     self.launch_detect_sign_launched = False
     self.launch_detect_sign.shutdown()
    else:
     pass
  elif launch_num == self.Launcher.launch_detect_level_crossing.value:
   if is_start == True:
    if self.launch_detect_sign_launched == False:
     self.launch_detect_sign = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_sign = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_level_crossing.launch"])
     self.launch_detect_sign_launched = True
     self.launch_detect_sign.start()
    else:
     pass
   else:
    if self.launch_detect_sign_launched == True:
     self.launch_detect_sign_launched = False
     self.launch_detect_sign.shutdown()
    else:
     pass
  elif launch_num == self.Launcher.launch_detect_sign.value:
   if is_start == True:
    if self.launch_detect_sign_launched == False:
     self.launch_detect_sign = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_sign = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_sign.launch"])
     self.launch_detect_sign_launched = True
     self.launch_detect_sign.start()
    else:
     pass
   else:
    if self.launch_detect_sign_launched == True:
     self.launch_detect_sign_launched = False
     self.launch_detect_sign.shutdown()
    else:
     pass    
  elif launch_num == self.Launcher.launch_detect_lane.value:
   if is_start == True:
    if self.launch_detect_lane_launched == False:
     self.launch_detect_lane = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_lane = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_lane.launch"])
     self.launch_detect_lane_launched = True
     self.launch_detect_lane.start()
    else:
     pass
   else:
    if self.launch_detect_lane_launched == True:
     self.launch_detect_lane_launched = False
     self.launch_detect_lane.shutdown()
    else:
     pass      
  elif launch_num == self.Launcher.launch_control_lane.value:
   if is_start == True:
    if self.launch_control_lane_launched == False:
     self.launch_control_lane = roslaunch.scriptapi.ROSLaunch()
     self.launch_control_lane = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_control/launch/turtlebot3_autorace_control_lane.launch"])
     self.launch_control_lane_launched = True
     self.launch_control_lane.start()
    else:
     pass
   else:
    if self.launch_control_lane_launched == True:
     self.launch_control_lane_launched = False
     self.launch_control_lane.shutdown()
    else:
     pass      
  elif launch_num == self.Launcher.launch_control_moving.value:
   if is_start == True:
    if self.launch_control_parking_launched == False:
     self.launch_control_parking = roslaunch.scriptapi.ROSLaunch()
     self.launch_control_parking = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_control/launch/turtlebot3_autorace_control_moving.launch"])  
     self.launch_control_parking_launched = True
     self.launch_control_parking.start()
    else:
     pass
   else:
    if self.launch_control_parking_launched == True:
     self.launch_control_parking_launched = False
     self.launch_control_parking.shutdown()
    else:
     pass
  elif launch_num == self.Launcher.launch_detect_tunnel.value:
   if is_start == True:
    if self.launch_detect_tunnel_launched == False:
     self.launch_detect_tunnel = roslaunch.scriptapi.ROSLaunch()
     self.launch_detect_tunnel = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/turtlebot3_autorace_detect_tunnel.launch"])  
     self.launch_detect_tunnel_launched = True
     self.launch_detect_tunnel.start()
    else:
     pass
   else:
    if self.launch_detect_tunnel_launched == True:
     self.launch_detect_tunnel_launched = False
     self.launch_detect_tunnel.shutdown()
    else:
     pass 
  elif launch_num == self.Launcher.launch_control_tunnel.value:
   if is_start == True:
    if self.launch_control_tunnel_launched == False:
     self.launch_control_tunnel = roslaunch.scriptapi.ROSLaunch()
     self.launch_control_tunnel = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_driving/launch/turtlebot3_autorace_control_tunnel.launch"])  
     self.launch_control_tunnel_launched = True
     self.launch_control_tunnel.start()
    else:
     pass
   else:
    if self.launch_control_tunnel_launched == True:
     self.launch_control_tunnel_launched = False
     self.launch_control_tunnel.shutdown()
    else:
     pass
 def main(self):
  rospy.spin()
if __name__ == '__main__':
 rospy.init_node('core_node_controller')
 node = CoreNodeController()
 node.main()