#!/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. ################################################################################ # Authors: Leon Jung, [AuTURBO] Kihoon Kim (https://github.com/auturbo), Gilbert, Ashe Kim import rospy, roslaunch import subprocess import os import sys from enum import Enum from std_msgs.msg import UInt8, Float64 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', '') # subscribes : status returned self.sub_construction_stamped = rospy.Subscriber('/detect/construction_stamped', UInt8, self.cbconstructionStamped, queue_size=1) self.sub_mode_control = rospy.Subscriber('/core/decided_mode', UInt8, self.cbReceiveMode, queue_size=1) # publishes orders self.pub_construction_order = rospy.Publisher('/detect/construction_order', UInt8, queue_size=1) self.pub_mode_return = rospy.Publisher('/core/returned_mode', UInt8, queue_size=1) self.CurrentMode = Enum('CurrentMode', 'idle lane_following construction') self.current_mode = self.CurrentMode.lane_following.value self.StepOfConstruction = Enum('StepOfConstruction', 'find_obstacle avoid_obstacle exit') self.current_step_construction = self.StepOfConstruction.find_obstacle.value self.Launcher = Enum('Launcher', 'launch_camera_ex_calib launch_detect_sign launch_detect_lane launch_control_lane launch_detect_construction launch_control_moving') 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_detect_construction_launched = False self.launch_control_lane_launched = False self.launch_control_moving_launched = False self.is_triggered = 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 cbconstructionStamped(self, construction_msg): rospy.loginfo("construction Step changed from %d", self.current_step_construction) self.current_step_construction = construction_msg.data if self.current_step_construction == self.StepOfConstruction.exit.value: self.current_mode = self.CurrentMode.lane_following.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): # lane_following if self.current_mode == self.CurrentMode.lane_following.value: rospy.loginfo("Current step : searching construction sign") rospy.loginfo("Go to next step : construction") 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_construction.value, False) self.fnLaunch(self.Launcher.launch_control_lane.value, True) self.fnLaunch(self.Launcher.launch_control_moving.value, False) # construction elif self.current_mode == self.CurrentMode.construction.value: rospy.loginfo("New trigger for construction") msg_pub_construction_order = UInt8() if self.current_step_construction == self.StepOfConstruction.find_obstacle.value: rospy.loginfo("Current step : find_obstacle") rospy.loginfo("Go to next setp : avoid_obstacle") msg_pub_construction_order.data = self.StepOfConstruction.find_obstacle.value 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, False) self.fnLaunch(self.Launcher.launch_detect_construction.value, True) self.fnLaunch(self.Launcher.launch_control_lane.value, True) self.fnLaunch(self.Launcher.launch_control_moving.value, False) elif self.current_step_construction == self.StepOfConstruction.avoid_obstacle.value: rospy.loginfo("Current step : avoid_obstacle") rospy.loginfo("Go to next step : exit") msg_pub_construction_order.data = self.StepOfConstruction.avoid_obstacle.value 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, False) self.fnLaunch(self.Launcher.launch_detect_construction.value, True) self.fnLaunch(self.Launcher.launch_control_lane.value, False) self.fnLaunch(self.Launcher.launch_control_moving.value, True) elif self.current_step_construction == self.StepOfConstruction.exit.value: rospy.loginfo("Current step : exit") msg_pub_construction_order.data = self.StepOfConstruction.exit.value 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_construction.value, False) self.fnLaunch(self.Launcher.launch_control_lane.value, True) self.fnLaunch(self.Launcher.launch_control_moving.value, False) rospy.sleep(2) self.pub_construction_order.publish(msg_pub_construction_order) 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/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_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/detect_sign_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_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/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_detect_construction.value: if is_start == True: if self.launch_detect_construction_launched == False: self.launch_detect_construction = roslaunch.scriptapi.ROSLaunch() self.launch_detect_construction = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_detect/launch/detect_construction.launch"]) self.launch_detect_construction_launched = True self.launch_detect_construction.start() else: pass else: if self.launch_detect_construction_launched == True: self.launch_detect_construction_launched = False self.launch_detect_construction.shutdown() 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_driving/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_moving_launched == False: self.launch_control_moving = roslaunch.scriptapi.ROSLaunch() self.launch_control_moving = roslaunch.parent.ROSLaunchParent(self.uuid, [self.ros_package_path + "turtlebot3_autorace_driving/launch/turtlebot3_autorace_control_moving.launch"]) self.launch_control_moving_launched = True self.launch_control_moving.start() else: pass else: if self.launch_control_moving_launched == True: self.launch_control_moving_launched = False self.launch_control_moving.shutdown() pass def main(self): rospy.spin() if __name__ == '__main__': rospy.init_node('core_node_controller') node = CoreNodeController() node.main()