def test_block_escaping(lidar_data): global STEP set_lidar_values(lidar_data) if not TURTLE.is_occupied(): if STEP == 1: TURTLE.set_speed("normal") # TURTLE.go_turn("right", 1, angular=2, speed=0.15) front = get_object_distance("front") rospy.logdebug("front: {}".format(front)) if front == 0 or front > 0.40: return else: TURTLE.turn(0.15, -6) elif STEP == 2: TURTLE.set_speed("normal") frontleft = get_object_distance("frontleft") rospy.logdebug("frontleft: {}".format(frontleft)) if frontleft == 0 or frontleft < 0.40: return else: rospy.sleep(rospy.Duration(1.8)) TURTLE.turn(0.13, 6) elif STEP == 3: TURTLE.set_speed("slow") else: return STEP += 1 else: print("IS OCCUPIED!")
def test_parking(image): global STEP if not TURTLE.is_occupied(): if STEP == 1: TURTLE.go_forward(0.5) elif STEP == 2: TURTLE.set_speed("normal") TURTLE.go_turn("right", 2) elif STEP == 3: TURTLE.go_forward(0.7) # for stopping for a while rospy.sleep(rospy.Duration(0.5)) elif STEP == 4: TURTLE.go_backward(1) elif STEP == 5: TURTLE.go_turn_backward(1.2) elif STEP == 6: TURTLE.go_forward(2) elif STEP == 7: TURTLE.set_speed("fast") TURTLE.set_speed_smooth("normal") # TURTLE.set_speed("normal") else: return STEP += 1
def process_lidar(lidar_data): """ process the lidar image """ if not SCHEDULER.is_lidar_enable(): return if SCHEDULER.is_lidar_occupied() or TURTLE.is_occupied(): return state = SCHEDULER.get_state() if SCHEDULER.debug_option["show_timer"] and (state != "construction"): SCHEDULER.check_time("lidar", min=0.4, stop_when_delay=False) set_lidar_values(lidar_data) state = SCHEDULER.get_state() front = get_object_distance("front") if (front < 0.15) and (front > 0): TURTLE.stop() return if state is "default": leftside = get_object_distance("leftside") print(leftside) if (leftside < 0.35) and (leftside > 0): rospy.Timer(rospy.Duration(5), SCHEDULER.release_lidar_occupied, oneshot=True) SCHEDULER.set_state("to_construction") return elif state is "to_construction": leftside = get_object_distance("leftside") print("to_construction: " + str(leftside)) if (leftside < 0.35) and (leftside > 0): SCHEDULER.set_state("construction") return # rospy.Timer( # rospy.Duration(0.15), SCHEDULER.release_lidar_occupied, oneshot=True # ) # process_construction() elif state is "construction": process_construction() elif state is "parking": process_parking()
def process_lidar(lidar_data): """ process the lidar image """ if not SCHEDULER.is_lidar_enable(): return if SCHEDULER.is_lidar_occupied() or TURTLE.is_occupied(): return state = SCHEDULER.get_state() if SCHEDULER.debug_option["show_timer"] and (state != "construction"): SCHEDULER.check_time("lidar", min=0.4, stop_when_delay=False) set_lidar_values(lidar_data) state = SCHEDULER.get_state() front = get_object_distance("front") if (front < 0.15) and (front > 0): TURTLE.stop() return # if STEP >= 10: # process_parking() # else: # process_construction() # return if state is "intersection_left": left = get_object_distance("left") if (left > 0) and (left < 0.50): TURTLE.set_speed("slow") SCHEDULER.set_state("to_construction") elif state is "to_construction": rospy.Timer(rospy.Duration(0.15), SCHEDULER.release_lidar_occupied, oneshot=True) process_construction_new() elif state is "construction": process_construction_new() elif state is "parking": process_parking() elif state is "tunnel": process_tunnel()
def process_construction(): """ process construction state """ global STEP global NUM_OBSTRUCTION global LANE_TO if TURTLE.is_occupied(): return if STEP == 0: leftside = get_object_distance("leftside") left = get_object_distance("left") if leftside > 0: rospy.logdebug("[PROC] LIDAR LEFTSIDE: {}".format( leftside)) if (leftside > 0) and (leftside < 0.40): STEP = 1 rospy.logdebug("[PROC] STEP changed to {}".format(STEP)) SCHEDULER.disable_cams() rospy.loginfo("[PROC] construction state started.") TURTLE.go_forward(3.5) rospy.sleep(rospy.Duration(0.5)) return else: return # elif (left > 0) and (left < 1.5): # STEP = 2 # rospy.logdebug("[PROC] STEP changed to {}".format(STEP)) # return # rospy.sleep(rospy.Duration(2)) elif STEP == 1: TURTLE.set_speed("normal") TURTLE.set_speed_smooth("slow") left = get_object_distance("left") if left > 0: rospy.logdebug("[PROC] LIDAR LEFT: {}".format( left)) if (left < 0.50) or (left > 1.5): return else: STEP = 3 rospy.logdebug("[PROC] STEP changed to {}".format(STEP)) return elif STEP == 2: # TODO: write code for first left lane pass elif STEP == 3: TURTLE.go_turn("left", speed=0.11) LANE_TO = "left" elif STEP == 4: TURTLE.set_speed("normal") reverse_lane() biased = get_object_distance(LANE_TO + "_biased") if biased > 0: rospy.logdebug("[PROC] LIDAR {:s}_BIASED: {}" .format(LANE_TO, biased)) reverse_lane() if (biased == 0) or (biased > 0.30): return TURTLE.go_turn(LANE_TO, duration=0.5, angular=4.2) TURTLE.set_speed("normal") # TURTLE.set_speed("fast") # if LANE_TO is "left": # TURTLE.turn(0.13, 1.3, consuming_time=1.5) # else: # TURTLE.turn(0.13, -1.3, consuming_time=1.5) rospy.sleep(rospy.Duration(2.2)) reverse_lane() elif STEP == 5: TURTLE.go_turn(LANE_TO, duration=0.7, angular=4.2) TURTLE.set_speed("normal") # TURTLE.set_speed("fast") # if LANE_TO is "left": # TURTLE.turn(0.13, 1.3, consuming_time=1.5) # else: # TURTLE.turn(0.13, -1.3, consuming_time=1.5) NUM_OBSTRUCTION += 1 if NUM_OBSTRUCTION < 2: STEP = 4 return elif STEP == 6: TURTLE.go_forward(1) rospy.sleep(rospy.Duration(0.6)) elif STEP == 7: TURTLE.go_turn("left", duration=0.8, angular=3) elif STEP == 8: TURTLE.set_speed("fast") TURTLE.set_speed_smooth("normal") TURTLE.go_forward(5) rospy.sleep(rospy.Duration(0.5)) elif STEP == 9: # NOTE: turn to parking step STEP = 10 SCHEDULER.set_state("parking") else: return STEP += 1 rospy.logdebug("[PROC] STEP changed to {}".format(STEP))
def process_tunnel(): """ process tunnel state """ if TURTLE.is_occupied(): return if STEP == 30: # TODO: turn to 45 degrees pass elif STEP == 31: TURTLE.set_speed("normal") # TURTLE.go_turn("right", 1, angular=2, speed=0.15) front = get_object_distance("front") left = get_object_distance("left") right = get_object_distance("right") rospy.logdebug( "front: {} left: {} right: {}".format(front, left, right)) if left < 0.20: # TODO: turn to variable degrees TURTLE.turn(0.15, -6) STEP = 34 return elif right < 0.20: # TODO: turn to variable degrees TURTLE.turn(-0.15, -6) STEP = 35 return elif front == 0 or front > 0.40: return else: TURTLE.turn(0.15, -6) TURTLE.turn(0.15, -6) elif STEP == 32: TURTLE.set_speed("normal") frontleft = get_object_distance("frontleft") rospy.logdebug("frontleft: {}".format(frontleft)) if frontleft == 0 or frontleft < 0.40: return else: rospy.sleep(rospy.Duration(1.8)) TURTLE.turn(0.13, 6) elif STEP == 33: TURTLE.set_speed("normal") frontleft = get_object_distance("frontleft") rospy.logdebug("frontleft: {}".format(frontleft)) if frontleft == 0 or frontleft < 0.40: return else: STEP = 31 return elif STEP == 34: front = get_object_distance("front") if front == 0 or front > 0.20: return # TODO : turn to left TURTLE.turn(-0.3, -6) elif STEP == 35: # NOTE: ending step TURTLE.set_speed("normal") else: return STEP += 1
def process_subcam(image): """ process the subcam image """ if not SCHEDULER.is_subcam_enable(): return if EYE.is_sub_occupied() or TURTLE.is_occupied(): return if SCHEDULER.debug_option["show_timer"]: SCHEDULER.check_time("subcam", min=0.25) info = EYE.see_sub(image) if info is None: # rospy.logwarn("[PROC] No Information!") return center = info["center"] slope = info["slope"] if slope < -0.5: # limit = 1.6 limit = 1.5 # For slow speed amplitude = 1.6 # elif slope > 0.5: # limit = 1.6 # amplitude = 1.2 else: # limit = 1.2 # amplitude = 1.2 limit = 1.2 # For slow speed amplitude = 1.2 # For slow speed if EYE.get_front_state() == "straight": if (abs(center) < 30) and slope < -0.4: degree = pow(abs(slope) / 1.8, 1.1) * amplitude elif center < 0: degree = pow(abs(center) / 100, 2.0) * amplitude elif center > 0: degree = - pow(abs(center) / 100, 2.0) * amplitude else: degree = 0 else: if (abs(center) < 30) and slope < -0.4: degree = pow(abs(slope) / 1.8, 0.9) * amplitude elif center < 0: degree = pow(abs(center) / 100, 1.9) * amplitude elif center > 0: degree = - pow(abs(center) / 100, 1.9) * amplitude else: degree = 0 buf_sum = sum(BUF_ANGULAR) if EYE.get_front_state() == "straight": adjust_angular = BUF_ANGULAR.pop(0) * 0.9 BUF_ANGULAR.append(degree) degree -= adjust_angular # if abs(buf_sum) > 1: else: reset_buffer() adjust_angular = 0 degree = max(min(degree, limit), -limit) if not info["has_line"]: if center < -55: # degree = 1.6 degree = 1.4 # For slow speed elif center > 50: degree = -1.2 # degree = -1.2 # For slow speed elif center > 10: # editing... degree = -0.9 # editing... else: degree = 1.4 # if SCHEDULER.debug_option["show_center_slope"]: # rospy.logdebug( # "[PROC] center: {:.2f} slope: {:.2f} degree: {:.2f} adj: {:.2f} buf_sum: {:.2f} {} {}".format( # center, slope, degree, adjust_angular, buf_sum, EYE.get_front_state(), info["has_line"]) # ) rospy.Timer( rospy.Duration(0.15), EYE.release_sub_occupied, oneshot=True ) TURTLE.turn(0.13, degree)
def process_construction_new(): """ process construction state """ global STEP global NUM_OBSTRUCTION global LANE_TO global BUF_ANGULAR global BUF_SIZE if TURTLE.is_occupied(): return if STEP == 0: # TURTLE.set_speed("normal") leftside = get_object_distance("leftside") left = get_object_distance("left") if leftside > 0: rospy.logdebug("[PROC] LIDAR LEFTSIDE: {}".format(leftside)) if (leftside > 0) and (leftside < 0.50) and (left > 1.00): EYE.check_yellow = False SCHEDULER.set_state("construction") rospy.loginfo("[PROC] construction state started.") STEP = 1 rospy.logdebug("[PROC] STEP changed to {}".format(STEP)) TURTLE.go_forward(3.5) return else: return elif STEP == 1: TURTLE.set_speed("normal") TURTLE.set_speed_smooth("slow") TURTLE.turn(0.13, 0) left = get_object_distance("left") leftback = get_object_distance("leftback") rospy.logdebug("[PROC] LIDAR LEFT: {:.2f} LEFTBACK: {:.2f}}".format( left, leftback)) if (left > 0) and (left < 0.50): return else: TURTLE.set_speed("slow") if (leftback > 0.5): # TURTLE.go_forward(2.5) STEP = 3 rospy.logdebug("[PROC] STEP changed to {}".format(STEP)) return elif STEP == 2: # TODO: write code for first left lane pass elif STEP == 3: TURTLE.set_speed("normal") TURTLE.set_speed_smooth("stop") front = get_object_distance("front") right_biased = get_object_distance("right_biased") if (front > 1.0) and (right_biased < 1.0) and (right_biased > 0.0): print("passed", front, right_biased) print("BUF_SIZE: ", BUF_SIZE) BUF_SIZE = 15 reset_buffer() TURTLE.set_speed_smooth("slow") pass elif front * right_biased == 0: return else: TURTLE.set_speed("stop") print("turning...", front, right_biased) TURTLE.turn(0.13, 1.0) # rospy.sleep(rospy.Duration(5.0)) return # TURTLE.go_turn("left") elif STEP == 4: right_biased = get_object_distance("right_biased") left_biased = get_object_distance("left_biased") front = get_object_distance("front") if right_biased == 0.0: right_biased = 3.0 if left_biased == 0.0: left_biased = 3.0 if front == 0.0: front = 3.0 elif front < 0.2: TURTLE.set_speed_smooth("stop") else: TURTLE.set_speed_smooth("slow") min_distance = min(right_biased, left_biased) degree = 0 if (front < 1.0): degree += max(pow(1.0 - front, 2), 0) else: degree += max(0.5 - min_distance, 0) * 3 # if min_distance < 0.5: # degree += max((0.5 - min_distance), 0) * 1.5 # elif (min_distance > 1.0) and (min_distance < 3.0): # degree = 0.2 if (left_biased == min_distance) and (min_distance < 0.5): degree *= -1 # max_distance = max(right_biased, left_biased) # if (left_biased == max_distance): # degree *= -1 # degree = 0 # if min_distance > 0 and min_distance < 0.5: # if right_biased > left_biased: # degree = (0.5 - min_distance) * (-7) # LANE_TO = "right" # elif right_biased < left_biased: # degree = (0.5 - min_distance) * (7) # LANE_TO = "left" # if is_left_crashable(): # degree = -1.7 # elif is_right_crashable(): # degree = 1.7 degree *= 3 degree = max(min(degree, 2.0), -2.0) BUF_ANGULAR.append(degree) degree -= BUF_ANGULAR.pop(0) print("BUF_ANGULAR:", BUF_ANGULAR) # if degree != 0: # BUF_ANGULAR.append(degree) # elif len(BUF_ANGULAR) > 9: # STEP = 5 if SCHEDULER.debug_option["show_construction_lidar"]: rospy.logdebug( "[PROC] r_based: {:.2f} l_based: {:.2f} min: {:.2f} front: {:.2f} deg: {:.2f}" .format(right_biased, left_biased, min_distance, front, degree)) TURTLE.turn(0.13, degree) return elif STEP == 5: print("[StEP 5]") if len(BUF_ANGULAR) > 0: TURTLE.turn(0.13, -BUF_ANGULAR.pop(0)) return else: front = get_object_distance("front") print(front) # if (front > 0) and (front < 1.0): # if LANE_TO == "right": # TURTLE.turn(0.13, 0.8) # else: # TURTLE.turn(0.13, -0.8) # return # else: if NUM_OBSTRUCTION < 1: NUM_OBSTRUCTION += 1 STEP = 4 return elif STEP == 6: TURTLE.go_forward(1) TURTLE.set_speed("normal") TURTLE.go_turn("left") TURTLE.set_speed("normal") TURTLE.set_speed("fast") TURTLE.set_speed_smooth("normal") TURTLE.go_forward(5) STEP = 10 SCHEDULER.set_state("parking") BUF_SIZE = 3 reset_buffer() return STEP += 1 rospy.logdebug("[PROC] STEP changed to {}".format(STEP))
def process_subcam(image): """ process the subcam image """ if not SCHEDULER.is_subcam_enable(): return if SCHEDULER.is_subcam_occupied() or TURTLE.is_occupied(): return info = EYE.see_sub(image) if SCHEDULER.debug_option["show_timer"]: # Check delay only if has line # SCHEDULER.check_time("subcam", min=0.28, stop_when_delay=info["has_line"]) SCHEDULER.check_time("subcam", min=0.28, stop_when_delay=False) if info is None: rospy.logwarn("[PROC] No Information!") return center = info["center"] slope = info["slope"] if slope < -0.5: limit = 1.6 amplitude = 1.0 else: limit = 1.2 amplitude = 0.8 limit /= 1.9 # amplitude /= 2 state = SCHEDULER.get_state() if (EYE.get_front_state() == "straight") and (state is not "zigzag"): if (abs(center) < 30) and slope < -0.4: degree = pow(abs(slope) / 1.8, 1.1) * amplitude elif center < 0: degree = pow(abs(center) / 100, 2.0) * amplitude / 2 elif center > 0: degree = -pow(abs(center) / 100, 2.0) * amplitude else: degree = 0 else: if slope < 0: degree = -pow(abs(slope) / 1.8, 2.9) * amplitude * 28.0 else: degree = pow(abs(slope) / 1.0, 1.2) * amplitude * 4.0 # degree = pow(abs(slope) / 1.8, 0.9) * amplitude # elif center < 0: # degree = pow(abs(center) / 100, 1.9) * amplitude # elif center > 0: # degree = - pow(abs(center) / 100, 1.9) * amplitude # else: # degree = 0 buf_sum = sum(BUF_ANGULAR) if EYE.get_front_state() == "straight": adjust_angular = BUF_ANGULAR.pop(0) * 0.9 BUF_ANGULAR.append(degree) degree -= adjust_angular # if abs(buf_sum) > 1: else: reset_buffer() adjust_angular = 0 degree = max(min(degree, limit), -limit) if not info["has_line"]: if center > 200: # degree = -1.2 degree = -1.1 # For enhancing frequency # elif EYE.get_front_state() == "straight": # degree = 0.6 else: # degree = 1.4 degree = 1.3 # For enhancing frequency # if not info["has_line"]: # if center < -55: # # degree = 1.6 # degree = 1.4 # For slow speed # elif center > 50: # degree = -1.2 # # degree = -1.2 # For slow speed # # elif center > 19: # # degree = -1.2 # else: # degree = 1.4 if SCHEDULER.debug_option["show_center_slope"]: rospy.logdebug( "[PROC] center: {:.2f} slope: {:.2f} degree: {:.2f} adj: {:.2f} buf_sum: {:.2f} {} {}" .format(center, slope, degree, adjust_angular, buf_sum, EYE.get_front_state(), info["has_line"])) rospy.Timer(rospy.Duration(0.15), SCHEDULER.release_subcam_occupied, oneshot=True) TURTLE.turn(0.13, degree)