def __init__(self, logdata=True): """ Handles difficult situations in which the car gets stuck """ super(CrisisDriver, self).__init__(logdata=logdata) self.iter = 0 self.driver = Driver(logdata=False) self.is_in_control = False self.approaches = [self.navigate_to_middle, self.original_implementation] self.previous_angles = [] self.previous_accels = [] self.previous_gears = [] self.bad_counter = 0 self.needs_help = False
def __init__(self, steering_values, global_max_speed): super(Final_Driver, self).__init__() self.steer = ffnn_steer.Steer(10) self.steer.load_state_dict(torch.load("./steer.data")) self.speed = ffnn_speed.Speed(10) self.speed.load_state_dict(torch.load("./ffnn_speed.data")) self.back_up_driver = Driver(logdata=False) self.bad_counter = 0 self.lap_counter = 0 self.brake_row = 0 self.angles = [90, 75, 60, 45, 30, 20, 15, 10, 5, 0, -5, -10, -15, -20, -30, -45, -60, -75, -90] self.alphas = [math.radians(x) for x in self.angles] self.last_opponents = [0 for x in range(36)] self.steering_values = steering_values self.global_max_speed = global_max_speed
def __init__(self, hostname='localhost', port=3001, *, driver=None, serializer=None, data=None): self.hostaddr = (hostname, port) self.driver = driver or Driver() self.serializer = serializer or Serializer() self.state = State.STOPPED self.socket = None self.datafile = data _logger.debug('Initializing {}.'.format(self)) self.crashed = False self.stuck = False self.fitness = 0 self.timespend = 0 self.stack = 0 self.count = 0 self.sumspeed = 0 self.speed = 0 self.position = 0 self.positionReward = 0 self.accelReward = 0 self.countOutside = 0
def __init__(self, model_file, H, depth, port, record_train_file=None, normalize=False): super().__init__(False) if normalize: self.norm = True else: self.norm = False # Select right model if depth == 3: self.model = train.ThreeLayerNet(22, H, 3) elif depth == 5: self.model = train.FiveLayerNet(22, H, 3) else: print("Using depth=2") self.model = train.TwoLayerNet(22, H, 3) # Load model self.model.load_state_dict( torch.load(model_file, map_location=lambda storage, loc: storage)) # Check if we want to record the actuator & sensor data self.record = False if record_train_file is not None: self.record = True self.file_handler = open(record_train_file, 'w') self.file_handler.write("ACCELERATION,BRAKE,STEERING,SPEED,\ TRACK_POSITION,ANGLE_TO_TRACK_AXIS,TRACK_EDGE_0,TRACK_EDGE_1,\ TRACK_EDGE_2,TRACK_EDGE_3,TRACK_EDGE_4,TRACK_EDGE_5,TRACK_EDGE_6,\ TRACK_EDGE_7,TRACK_EDGE_8,TRACK_EDGE_9,TRACK_EDGE_10,\ TRACK_EDGE_11,TRACK_EDGE_12,TRACK_EDGE_13,TRACK_EDGE_14,\ TRACK_EDGE_15,TRACK_EDGE_16,TRACK_EDGE_17,TRACK_EDGE_18") self.is_leader = True self.helper = StupidDriver(self.record) self.standard_driver = Driver() self.race_started = False self.recovers = 0 self.recover_mode = False self.speeds = [] self.dict = {} self.dict["crashes"] = [] self.crash_recorded = False self.dict_teammate = {} self.port = port self.partner = -1 path = os.path.abspath(os.path.dirname(__file__)) for i in os.listdir(path): if os.path.isfile(os.path.join(path, i)) and 'mjv_partner' in i: try: os.remove(path + "/" + i) except: pass
def test_init_encoding(): d = Driver(False) s = Serializer() data = {'init': d.range_finder_angles} encoded = s.encode(data, prefix='SCR') assert encoded == b'SCR(init -90 -75 -60 -45 -30 -20 -15 -10 -5 0 5 10 15 20 30 45 60 75 90)'
def __init__(self, hostname='localhost', port=3001, *, driver=None, serializer=None): self.hostaddr = (hostname, port) self.driver = driver or Driver() self.serializer = serializer or Serializer() self.state = State.STOPPED self.socket = None _logger.debug('Initializing {}.'.format(self))
def __init__(self, hostname='localhost', port=3001, *, driver=None, serializer=None): self.hostaddr = (hostname, port) self.driver = driver or Driver() self.serializer = serializer or Serializer() self.state = State.STOPPED self.socket = None self.fitness = -1. self.offroad_count = 0 self.turn_around_count = 0 self.negative_speed_count = 0 _logger.debug('Initializing {}.'.format(self))
def test_special_messages(mock_socket_ctor): mock_socket = mock.MagicMock() mock_socket_ctor.return_value = mock_socket mock_driver = mock.MagicMock() mock_driver.range_finder_angles = Driver(False).range_finder_angles client = Client(driver=mock_driver) assert client.state is State.STOPPED mock_socket.recvfrom = mock.MagicMock(side_effect=[(b'***identified***', None), (b'***restart***', None), (b'***shutdown***', None)]) client.run() assert client.state is State.STOPPED # not supported on server side assert mock_driver.on_restart.call_count == 1 assert mock_driver.on_shutdown.call_count == 1
def __init__(self, model_file, H, depth, record_train_file=None, normalize=False): super().__init__(False) if normalize: self.norm = True else: self.norm = False # Select right model if depth == 3: self.model = train.ThreeLayerNet(22, H, 3) elif depth == 5: self.model = train.FiveLayerNet(22, H, 3) else: print("Using depth=2") self.model = train.TwoLayerNet(22, H, 3) # Load model self.model.load_state_dict(torch.load( model_file, map_location=lambda storage, loc: storage)) # Check if we want to record the actuator & sensor data self.record = False if record_train_file is not None: self.record = True self.file_handler = open(record_train_file, 'w') self.file_handler.write("ACCELERATION,BRAKE,STEERING,SPEED,\ TRACK_POSITION,ANGLE_TO_TRACK_AXIS,TRACK_EDGE_0,TRACK_EDGE_1,\ TRACK_EDGE_2,TRACK_EDGE_3,TRACK_EDGE_4,TRACK_EDGE_5,TRACK_EDGE_6,\ TRACK_EDGE_7,TRACK_EDGE_8,TRACK_EDGE_9,TRACK_EDGE_10,\ TRACK_EDGE_11,TRACK_EDGE_12,TRACK_EDGE_13,TRACK_EDGE_14,\ TRACK_EDGE_15,TRACK_EDGE_16,TRACK_EDGE_17,TRACK_EDGE_18") self.is_leader = True self.helper = StupidDriver(self.record) self.standard_driver = Driver() self.race_started = False self.recovers = 0 self.recover_mode = False self.speeds = [] self.number = 1
def __init__(self, hostname='localhost', port=3001, *, driver=None, serializer=None, fitnessFile='neat/fitnessFile'): self.hostaddr = (hostname, port) self.driver = driver or Driver() self.serializer = serializer or Serializer() self.state = State.STOPPED self.socket = None self.evaluation = { 'crashed': False, 'stuck': False, 'fitness': 0, 'time': 0, 'avgSpeed': 0, 'position': 0, 'steering': 0, 'iteration': 1, 'lapComplete': False } self.priorities = { 'speed': 5, 'distance': 1, 'crashPenalty': 0, 'steeringPenalty': 100, } self.fitnessFile = fitnessFile _logger.debug('Initializing {}.'.format(self))
type=str ) parser.add_argument('-v', help='Debug log level.', action='store_true') #args = parser.parse_args() args, _ = parser.parse_known_args() # switch log level: if args.v: level = logging.DEBUG else: level = logging.INFO del args.v logging.basicConfig( level=level, format="%(asctime)s %(levelname)7s %(name)s %(message)s" ) # start client loop: client = Client(driver=driver, **args.__dict__) client.run() if __name__ == '__main__': main(Driver())
class Final_Driver(Driver): def __init__(self, steering_values, global_max_speed): super(Final_Driver, self).__init__() self.steer = ffnn_steer.Steer(10) self.steer.load_state_dict(torch.load("./steer.data")) self.speed = ffnn_speed.Speed(10) self.speed.load_state_dict(torch.load("./ffnn_speed.data")) self.back_up_driver = Driver(logdata=False) self.bad_counter = 0 self.lap_counter = 0 self.brake_row = 0 self.angles = [90, 75, 60, 45, 30, 20, 15, 10, 5, 0, -5, -10, -15, -20, -30, -45, -60, -75, -90] self.alphas = [math.radians(x) for x in self.angles] self.last_opponents = [0 for x in range(36)] self.steering_values = steering_values self.global_max_speed = global_max_speed def update_trackers(self, carstate): if carstate.current_lap_time == 0: self.lap_counter += 1 print("Lap={}".format(self.lap_counter)) print("distance:",carstate.distance_raced) def drive(self, carstate: State) -> Command: self.update_trackers(carstate) if self.in_a_bad_place(carstate): command = self.back_up_driver.drive(carstate) if self.bad_counter >= 600 and is_stuck(carstate): # we try reversing command.gear = -command.gear if command.gear < 0: command.steering = -command.steering command.gear = -1 self.bad_counter = 200 else: # since the data and python's values differ we need to adjust them carstate.angle = math.radians(carstate.angle) carstate.speed_x = carstate.speed_x*3.6 command = self.make_next_command(carstate) # based on target, implement speed/steering manually print("Executing command: gear={}, acc={}, break={}, steering={}".format(command.gear, command.accelerator, command.brake, command.steering)) return command def make_next_command(self, carstate): command = Command() # we switch gears manually gear = self.gear_decider(carstate) # we get the steering prediction steer_pred = self.steer_decider(carstate, steering_values=self.steering_values) # steer_pred = self.steer_decider_nn(carstate) # pedal =[-1;1], combining breaking and accelerating to one variable pedal = self.speed_decider(carstate, max_speed=self.global_max_speed) # make sure we don't drive at people opponents_deltas = list(map(sub, carstate.opponents, self.last_opponents)) steer_pred, pedal = self.deal_with_opponents(steer_pred, pedal, carstate.speed_x, carstate.distance_from_center, carstate.opponents, opponents_deltas) # disambiguate pedal with smoothing brake, accel = self.disambiguate_pedal(pedal, accel_cap=1.0, break_cap=0.75, break_max_length=5) command.brake = brake command.accelerator = accel command.steering = steer_pred command.gear = gear return command def deal_with_opponents(self, steer_pred, pedal, speed, distance_from_center, opponents_new, opponents_delta): # index 18 is in front # index 35 in behind us adjustment = 0.1 # if there are cars infront-left -> move to right if opponents_new[17] < 10 or opponents_new[16] < 10 or opponents_new[15] < 10: print("ADJUSTING SO NOT TO HIT") steer_pred -= adjustment if opponents_new[19] < 10 or opponents_new[20] < 10 or opponents_new[21] < 10: print("ADJUSTING SO NOT TO HIT") # move to left steer_pred += adjustment if opponents_new[18] < 50: # we are on left side -> move right if distance_from_center > 0: steer_pred -= adjustment # o.w. move left else: steer_pred += adjustment if speed > 100: # we are getting closer to the car in front (and we can't avoid it). We need to slow down a bit if (opponents_delta[18] < 0 and opponents_new[18] < 20) or (opponents_delta[17] < 0 and opponents_new[17] < 4) or (opponents_delta[19] < 0 and opponents_new[19] < 4): pedal -= 0.1 return steer_pred, pedal def disambiguate_pedal(self, pedal, accel_cap=0.5, break_cap=0.75, break_max_length=5): if pedal >= 0.0: accelerator = pedal*accel_cap brake = 0 else: # we need to make sure that we don't break hard enough and not too long self.brake_row += 1 if self.brake_row <= break_max_length: brake = abs(pedal)*break_cap else: self.brake_row = 0 brake = 0 accelerator = 0 return brake, accelerator def steer_decider(self, carstate, steering_values): alpha_index = np.argmax(carstate.distances_from_edge) if is_straight_line(carstate=carstate, radians=self.alphas[alpha_index], factor=steering_values[4]): return carstate.angle*0.5 steering_function = lambda index, offset: (self.alphas[index-offset]*carstate.distances_from_edge[index-offset] + self.alphas[index+offset]*carstate.distances_from_edge[index+offset])/(carstate.distances_from_edge[index+offset]+carstate.distances_from_edge[index-offset]) steer = steering_values[0]*self.alphas[alpha_index] for x in range(1, 4): if alpha_index - x > -1 and alpha_index + x < len(steering_values): steer += steering_values[x]*steering_function(alpha_index, x) return steer def speed_decider(self, carstate, max_speed=120): # we predict speed and map that to pedal x_in = ffnn_speed.carstate_to_variable(carstate) target_speed = self.speed(x_in).data[0] # we limit the speed if target_speed >= max_speed: target_speed = max_speed pedal = 2/(1 + np.exp(carstate.speed_x - target_speed))-1 return pedal def gear_decider(self, carstate): gear = carstate.gear rpm = carstate.rpm # we do gears by hand # up if {9500 9500 9500 9500 9000} # down if {4000 6300 7000 7300 7300} if gear == -1: return 1 elif gear == 0: if rpm >= 5000: gear = 1 elif gear == 1: if rpm >= 9500: gear = 2 elif gear == 2: if rpm >= 9500: gear = 3 elif rpm <= 4000: gear = 2 elif gear == 3: if rpm >= 9500: gear = 4 elif rpm <= 6300: gear = 3 elif gear == 4: if rpm >= 9500: gear = 5 elif rpm <= 7000: gear = 3 elif gear == 5: if rpm >= 9000: gear = 6 elif rpm <= 7300: gear = 4 elif gear == 6: if rpm <= 7300: gear = 5 return gear def in_a_bad_place(self, carstate): something_wrong = False if is_offroad(carstate): print("I'm offroad!") something_wrong = True if is_reversed(carstate): print("I'm reversed!") something_wrong = True if is_stuck(carstate): print("I'm stuck!") something_wrong = True if (something_wrong): self.bad_counter += 1 else: self.bad_counter = 0 # if we have been in a bad place for 2 seconds if self.bad_counter >= 100: return True return False
default='Driver1') parser.add_argument('-u', '--unstuck', help='Make the drivers automatically try to unstuck', action='store_true') args, _ = parser.parse_known_args() print(args.parameters_file) print(args.output_file) print(args.driver) if args.parameters_file is not None: driver = registry[args.driver](args.parameters_file, out_file=args.output_file, unstuck=args.unstuck) else: driver = Driver() try: main(driver) except Exception as exc: traceback.print_exc() if args.parameters_file is not None: driver.saveResults() raise
# action='store_true' # ) args, _ = parser.parse_known_args() print(args.driver_config) print(args.out_file) if args.out_file is not None: out_dir = os.path.dirname(args.out_file) if not os.path.exists(out_dir): os.makedirs(out_dir) if args.driver_config is not None: driver = SubsumptionDriver(**args.__dict__) else: driver = Driver() try: main(driver) except Exception as exc: traceback.print_exc() if args.driver_config is not None: driver.saveResults() raise
class CrisisDriver(Driver): def __init__(self, logdata=True): """ Handles difficult situations in which the car gets stuck """ super(CrisisDriver, self).__init__(logdata=logdata) self.iter = 0 self.driver = Driver(logdata=False) self.is_in_control = False self.approaches = [self.navigate_to_middle, self.original_implementation] self.previous_angles = [] self.previous_accels = [] self.previous_gears = [] self.bad_counter = 0 self.needs_help = False def drive(self, carstate): """ Gets the car out of a difficult situation Tries different approaches and gives each one a time out. A class level variable keeps track of the current approach across game cycles. If the timer runs out, the approach is terminated and the next approach gets initiated. Args: carstate: All parameters packed in a State object Returns: command: The next move packed in a Command object """ command = Command() command.accelerator = 0 self.appr_counter += 1 if self.appr_counter > APPROACH_TIMEOUT: self.next_approach() try: command = self.approaches[self.approach](carstate, command) self.previous_accels.append(command.accelerator) self.previous_gears.append(command.gear) except Exception as e: err(self.iter, "ERROR:", str(e)) return command def pass_control(self, carstate): """ Initializes a new crisis that has not been handled yet Args: carstate: The original carstate """ err(self.iter,"CRISIS: control received") self.is_in_control = True self.approach = 0 self.appr_counter = 0 # check if car in front # check if car behind # check track angle and side of the road # determine reverse or straight ahead def return_control(self): """ Passes control back to the main driver """ err(self.iter,"CRISIS: control returned") self.is_in_control = False self.needs_help = False def next_approach(self): """ Adjusts state to next approach """ self.approach += 1 self.appr_counter = 0 if self.approach >= len(self.approaches): self.approach -= 1 self.return_control() else: err(self.iter,"CRISIS: next approach:", self.approaches[self.approach].__name__) def approach_succesful(self): """ Called when a technique finished executing """ err(self.iter,"CRISIS: approach succesful:", self.approaches[self.approach].__name__) if self.has_problem: self.next_approach() else: self.return_control() def update_status(self, carstate): """ Updates the status of the car regarding its problems Args: carstate: The full carstate """ self.iter += 1 if len(self.previous_angles) >= MAX_ANGLES: self.previous_angles.pop(0) self.previous_angles.append(carstate.angle) if len(self.previous_accels) >= MAX_ACCELS: self.previous_accels.pop(0) self.previous_gears.append(sign(carstate.gear)) if len(self.previous_gears) >= MAX_GEARS: self.previous_gears.pop(0) self.is_on_left_side = sign(carstate.distance_from_center) == DFC_L self.is_on_right_side = not self.is_on_left_side self.faces_left = sign(carstate.angle) == ANG_L self.faces_right = not self.faces_left self.faces_front = abs(carstate.angle) < 90 self.faces_back = not self.faces_front self.faces_middle = self.is_on_left_side == self.faces_right self.is_standing_still = abs(carstate.speed_x) < 0.1 self.has_car_in_front = car_in_front(carstate.opponents) self.has_car_behind = car_behind(carstate.opponents) self.is_blocked = blocked(self.previous_accels, self.previous_gears, carstate.speed_x) self.is_off_road = max(carstate.distances_from_edge) == -1 self.is_reversed = self.faces_back self.is_going_in_circles = going_in_circles(self.previous_angles) self.is_traveling_sideways = abs(carstate.speed_y) > 15 self.has_problem = self.is_off_road or \ self.is_going_in_circles or \ self.is_blocked or \ self.is_reversed or \ self.is_traveling_sideways if self.has_problem: self.bad_counter += 1 if self.bad_counter >= BAD_COUNTER_THRESHOLD: if self.is_off_road: debug(self.iter, " off road") if self.is_going_in_circles: debug(self.iter, " going in circles") if self.is_blocked: debug(self.iter, " blocked") if self.is_reversed: debug(self.iter, " reversed") self.needs_help = True else: self.bad_counter = 0 self.needs_help = False # # Approach Implementations # def original_implementation(self, carstate, command): """ approach 0) Args: carstate: The full carstate as passed down by the server command: The command to adjust """ if not self.is_off_road and abs(carstate.angle) < CTR_ANG_MARGIN: self.approach_succesful() command.gear, carstate.gear = 1, 1 command = self.driver.drive(carstate) # TODO is this legal? is_stuck = abs(carstate.speed_x) <= 5 and carstate.current_lap_time >= 10 #if self.bad_counter >= BAD_COUNTER_MANUAL_THRESHOLD and is_stuck: # we try reversing # command.gear = -command.gear # if command.gear < 0: # command.steering = -command.steering # command.gear = -1 # self.bad_counter = 200 command.accelerator /= 2.0 return command def navigate_to_middle(self, carstate, command): """ Finds it way to the middle of the road by driving in reverse approach 1) reverse towards the road, then once on the road, reverse towards the the middle until facing foward with an angle that's within the margin Args: carstate: The full carstate as passed down by the server command: The command to adjust """ debug(self.iter,"CRISIS: navigate_to_middle") dfc = carstate.distance_from_center if self.is_off_road: dist_spd = 2 if abs(dfc) > 10 else 1 perp_angle = 90 * sign(dfc) if self.faces_middle: debug(self.iter," off road and facing road") diff_with_perp_angle = perp_angle - carstate.angle if not abs(diff_with_perp_angle) < PRP_ANG_MARGIN: command.steering = sign(diff_with_perp_angle) * STR_R command.gear = 1 command.accelerator = OFF_ROAD_ACC * dist_spd else: debug(self.iter," off road and not facing road") diff_with_perp_angle = perp_angle + carstate.angle if not abs(diff_with_perp_angle) < PRP_ANG_MARGIN: command.steering = sign(diff_with_perp_angle) * STR_R command.gear = -1 command.accelerator = OFF_ROAD_REV_ACC * dist_spd else: if abs(carstate.angle) < CTR_ANG_MARGIN: self.approach_succesful() else: if self.faces_middle or abs(carstate.angle) < 50: # TODO globalize debug(self.iter," on road facing middle") command.steering = to_ang(carstate.angle) command.gear = 1 command.accelerator = ACC elif abs(dfc) > 0.5: debug(self.iter," on road not facing middle") command.steering = away_from_ang(carstate.angle) command.gear = -1 command.accelerator = REV_ACC if self.is_blocked: command.gear = 1 command.accelerator *= 2 debug(self.iter, "ang=%.2f, spd=%.2f, dfc=%.2f" %(carstate.angle, carstate.speed_x, carstate.distance_from_center)) debug(self.iter, "ste=%.2f, acc=%.2f, gea=%.2f" %(command.steering, command.accelerator, command.gear)) # when spinning out of control, don't do anything if self.is_traveling_sideways or self.is_going_in_circles: command.acceleration = 0 gstc = GEAR_SHIFTING_TRANSITION_CYCLES # braking when shifting gear so it doesn't continue its course if any(not g == command.gear for g in self.previous_gears[-gstc:]): command.brake = 1 command.acceleration = 0 # faster acceleration after having shifted gears elif any(not g == command.gear for g in self.previous_gears[-gstc*2:-gstc]): command.brake = 0 command.acceleration = 1.0 return command