def place_agents_along_linestring(self, world, linestring, s_start, s_end, agent_params, goal_definition): s = s_start if s_end < s_start: linestring.reverse() s = s_end s_end = s_start agent_list = [] while s < s_end: # set agent state on linestring with random velocity xy_point = get_point_at_s(linestring, s) angle = get_tangent_angle_at_s(linestring, s) velocity = self.sample_velocity_uniform(self._other_velocity_range) agent_state = np.array([0, xy_point.x(), xy_point.y(), angle, velocity ]) agent_params = self._agent_params.copy() agent_params["state"] = agent_state agent_params["goal_definition"] = goal_definition agent_params["map_interface"] = world.map converter = ModelJsonConversion() bark_agent = converter.agent_from_json(agent_params, self._params) agent_list.append(bark_agent) # move forward on linestring based on vehicle size and max/min distance s += bark_agent.shape.front_dist + bark_agent.shape.rear_dist + \ self.sample_distance_uniform(self._vehicle_distance_range) return agent_list
def initialize_params(self, params): self._local_params = \ self._params["Scenario"]["Generation"]["DeterministicScenarioGeneration"] self.goal_frame_center = self._local_params["goal_frame"][ "center_pose", "Center pose of the goal frames", [0, 0, 0]] self.goal_frame_points = self._local_params["goal_frame"][ "polygon_points", "Points of the goal frame polygon", [[-0.2, 1], [0.2, 1], [0.2, -1], [-0.2, -1], [-0.2, 1]]] self.goal_frame_poses = self._local_params[ "goal_poses", "A list with x,y, theta specyfing the sequence of the goal frames", [[5, 10, 3.14 / 2 + 0.01], [10, 15, 3.14 / 4], [20, 10, 3.14 / 2], [15, 2, 3.14 / 2 - 0.7]]] json_converter = ModelJsonConversion() _agent_params = json_converter.agent_to_json( self.default_drone_model()) if not isinstance(_agent_params, dict): _agent_params = _agent_params.convert_to_dict() self.drone_params = self._local_params[ "drones", "list of dictionaries with drone definitions", [{ "drone_model": _agent_params }]] self.ego_agent_id = self._local_params["ego_agent_id", "ID of the ego-agent", 0]
def initialize_params(self, params): self._local_params = \ self._params["Scenario"]["Generation"]["DeterministicScenarioGeneration"] self._map_file_name = self._local_params[ "MapFilename", "Path to the open drive map", "modules/runtime/tests/data/Crossing8Course.xodr"] self._json_converter = ModelJsonConversion()
def initialize_params(self, params): params_temp = \ self._params["Scenario"]["Generation"]["UniformVehicleDistribution"] self._random_seed = 1000 # since ScenarioGeneration UniformVehicleDistribution # will soon be deprecated we introduce this hack self._map_file_name = params_temp[ "MapFilename", "Path to the open drive map", "modules/runtime/tests/data/city_highway_straight.xodr", ] self._ego_goal_end = params_temp[ "EgoGoalEnd", "The center of the ego agent's goal region polygon", [5117, 5200]] self._ego_goal_start = params_temp[ "EgoGoalStart", "The coordinates of the start of the ego goal,\ if empty only ego goal end is used as center of polygon ", []] self._ego_goal_state_limits = params_temp[ "EgoGoalStateLimits", "x,y and theta limits around center line of lane between start and end applied to both lateral sides \ (only valid if start and end goal of ego are given)", [0.1, 0, 0.08]] self._ego_route = params_temp[ "EgoRoute", "A list of two points defining start and end point of initial ego driving corridor. \ If empty, then one of the other agents is selected as ego agents.", [[5117.5, 5100], [5117.5, 5200]]] self._others_source = params_temp[ "OthersSource", "A list of points around which other vehicles spawn. \ Points should be on different lanes. XodrLanes must be near these points \ (<0.5m) Provide a list of lists with x,y-coordinates", [[5114.626, 5061.8305]]] self._others_sink = params_temp[ "OthersSink", "A list of points defining end of other vehicles routes.\ Points should be on different lanes and match the order of the\ source points. XodrLanes must be near these points (<0.5m) \ Provide a list of lists with x,y-coordinates", [[5114.626, 5193.1725]]] assert len(self._others_sink) == len(self._others_source) self._vehicle_distance_range = params_temp["VehicleDistanceRange", "Distance range between vehicles in meter given as tuple from which" + \ "distances are sampled uniformly", (10, 20)] self._other_velocity_range = params_temp["OtherVehicleVelocityRange", "Lower and upper bound of velocity in km/h given as tuple from which" + \ " velocities are sampled uniformly", (20,30)] self._ego_velocity_range = params_temp["EgoVehicleVelocityRange", "Lower and upper bound of velocity in km/h given as tuple from which" + \ " velocities are sampled uniformly", (20,30)] json_converter = ModelJsonConversion() self._agent_params = params_temp[ "VehicleModel", "How to model the other agents", json_converter.agent_to_json(self.default_agent_model())] if not isinstance(self._agent_params, dict): self._agent_params = self._agent_params.convert_to_dict() np.random.seed(self._random_seed)
def create_single_scenario(self): scenario = Scenario(map_file_name=None, json_params=self._params.convert_to_dict()) scenario._agent_list = [] for agent_json in self.drone_params: agent_json["drone_model"]["map_interface"] = None agent_json["drone_model"][ "goal_definition"] = self._build_sequential_goal_definition() json_converter = ModelJsonConversion() agent = json_converter.agent_from_json( agent_json["drone_model"], param_server=self._local_params) agent.set_agent_id(agent_json["drone_model"]["id"]) scenario._agent_list.append(agent) scenario._eval_agent_ids = [ self._local_params["EgoAgentId", "ID of the ego-agent", 0] ] return scenario
def initialize_params(self, params): self._local_params = \ self._params["Scenario"]["Generation"]["DeterministicDroneChallengeGeneration"] self.goal_frame_center = self._local_params["goal_frame"][ "center_pose", "Center pose of the goal frames", [1, 0, 0]] self.goal_frame_points = self._local_params["goal_frame"][ "polygon_points", "Points of the goal frame polygon", [[0., 0.], [2., 0.], [2., 0.5], [0., 0.5], [0., 0.]]] self.goal_frame_poses = self._local_params[ "goal_poses", "A list with x,y, theta specyfing the sequence of the goal frames", [[5, 10, -0.3], [10, 15, -1.2], [20, 10, -2.9], [15, 2, -3.9]]] self._map_file_name = self._local_params[ "MapFilename", "Path to the open drive map", "modules/runtime/tests/data/Crossing8Course.xodr"] self._json_converter = ModelJsonConversion()
def initialize_params(self, params): params_temp = self.params["Scenario"]["Generation"][ "UniformVehicleDistribution"] self.map_file_name = params_temp[ "MapFilename", "Path to the open drive map", "modules/runtime/tests/data/Crossing8Course.xodr"] self.ego_goal = params_temp[ "EgoGoal", "The center of the ego agent's goal region polygon", [-191.789, -50.1725]] self.others_source = params_temp[ "OthersSource", "A list of points around which other vehicles spawn. \ Points should be on different lanes. Lanes must be near these points (<0.5m) \ Provide a list of lists with x,y-coordinates", [[-16.626, -14.8305]]] self.others_sink = params_temp[ "OthersSink", "A list of points around which other vehicles are deleted. \ Points should be on different lanes and match the order of the source points. \ Lanes must be near these points (<0.5m) \ Provide a list of lists with x,y-coordinates", [[-191.789, -50.1725]]] assert len(self.others_sink) == len(self.others_source) self.vehicle_distance_range = params_temp[ "VehicleDistanceRange", "Distance range between vehicles in meter given as tuple from which distances are sampled uniformly", (40, 50)] self.velocity_range = params_temp[ "VehicleVelocityRange", "Lower and upper bound of velocity in km/h given as tuple from which velocities are sampled uniformly", (20, 30)] json_converter = ModelJsonConversion() self.agent_params = params_temp["VehicleModel", "How to model the agent", \ json_converter.agent_to_json(self.default_agent_model())] if not isinstance(self.agent_params, dict): self.agent_params = self.agent_params.convert_to_dict() np.random.seed(self.random_seed)
def agent_from_trackfile(track_params, param_server, agent_id): fname = track_params["filename"] track_id = track_params["track_id"] track = track_from_trackfile(fname, track_id) start = track_params["start_offset", "The timestamp in ms when to start the trajectory", None] end = track_params["end_offset", "The timestamp in ms when to end the trajectory", None] behavior_model = track_params["behavior_model"] if start is None: start = track.time_stamp_ms_first if end is None: end = track.time_stamp_ms_last model_converter = ModelJsonConversion() if behavior_model is None: # each agent need's its own param server behavior = behavior_from_track( track, param_server.addChild("agent{}".format(agent_id)), start, end) else: behavior = model_converter.convert_model(behavior_model, param_server) bark_agent = Agent( init_state_from_track(track, start), behavior, model_converter.convert_model(track_params["dynamic_model"], param_server), model_converter.convert_model(track_params["execution_model"], param_server), shape_from_track( track, param_server["DynamicModel"] ["wheel_base", "Distance between front and rear wheel center", 2.7]), param_server.addChild("agent{}".format(agent_id)), goal_definition_from_track(track, end), track_params["map_interface"]) # set agent id from track bark_agent.SetAgentId(track_id) return bark_agent
def create_single_scenario(self): scenario = Scenario(map_file_name=self._map_file_name, json_params=self._params.convert_to_dict()) world = scenario.get_world_state() agent_list = [] # OTHER AGENTS for idx, source in enumerate(self._others_source): connecting_center_line, s_start, s_end, _, lane_id_end = \ self.center_line_between_source_and_sink(world.map, source, self._others_sink[idx]) goal_polygon = Polygon2d([0, 0, 0], [Point2d(-1.5,0), Point2d(-1.5,8), Point2d(1.5,8), Point2d(1.5,0)]) goal_polygon = goal_polygon.translate(Point2d(self._others_sink[idx][0], self._others_sink[idx][1])) goal_definition = GoalDefinitionPolygon(goal_polygon) agent_list.extend( self.place_agents_along_linestring(world, connecting_center_line, s_start, s_end, self._agent_params, goal_definition)) description=self._params.convert_to_dict() description["ScenarioGenerator"] = "UniformVehicleDistribution" # EGO AGENT ego_agent=None if len(self._ego_route) == 0: # take agent in the middle of list num_agents = len(agent_list) ego_agent = agent_list[math.floor(num_agents/4)] else: connecting_center_line, s_start, s_end, _, lane_id_end = \ self.center_line_between_source_and_sink(world.map, self._ego_route[0], self._ego_route[1]) sego = self.sample_srange_uniform([s_start, s_end]) xy_point = get_point_at_s(connecting_center_line, sego) angle = get_tangent_angle_at_s(connecting_center_line, sego) velocity = self.sample_velocity_uniform(self._ego_velocity_range) agent_state = np.array([0, xy_point.x(), xy_point.y(), angle, velocity ]) agent_params = self._agent_params.copy() agent_params["state"] = agent_state # goal for driving corridor generation goal_polygon = Polygon2d([0, 0, 0], [Point2d(-1.5,0), Point2d(-1.5,8), Point2d(1.5,8), Point2d(1.5,0)]) goal_polygon = goal_polygon.translate(Point2d(self._ego_route[1][0], self._ego_route[1][1])) goal_definition = GoalDefinitionPolygon(goal_polygon) agent_params["goal_definition"] = goal_definition agent_params["map_interface"] = world.map converter = ModelJsonConversion() ego_agent = converter.agent_from_json(agent_params, self._params) # TODO(@bernhard): ensure that ego agent not collides with others agent_list.append(ego_agent) # EGO Agent Goal Definition if len(self._ego_goal_start) == 0: if len(self._ego_route) == 0: # ego agent is one of the random agents, so the goal definition is # already set pass else: goal_polygon = Polygon2d([0, 0, 0], [Point2d(-1.5,0), Point2d(-1.5,8), Point2d(1.5,8), Point2d(1.5,0)]) goal_polygon = goal_polygon.translate(Point2d(self._ego_goal_end[0], self._ego_goal_end[1])) ego_agent.goal_definition = GoalDefinitionPolygon(goal_polygon) ego_agent.generate_local_map() else: connecting_center_line, s_start, s_end, _, lane_id_end = \ self.center_line_between_source_and_sink(world.map, self._ego_goal_start, self._ego_goal_end) goal_center_line = get_line_from_s_interval(connecting_center_line, s_start, s_end) # build polygon representing state limits lims = self._ego_goal_state_limits goal_limits_left = goal_center_line.translate(Point2d(-lims[0], -lims[1])) goal_limits_right = goal_center_line.translate(Point2d(lims[0], lims[1])) goal_limits_right.reverse() goal_limits_left.append_linestring(goal_limits_right) polygon = Polygon2d([0,0,0], goal_limits_left) ego_agent.goal_definition = GoalDefinitionStateLimits(polygon, (1.57-0.08, 1.57+0.08)) # only one agent is ego in the middle of all other agents scenario._agent_list = agent_list scenario._eval_agent_ids = [ego_agent.id] return scenario