Improved option dictionaries

This commit is contained in:
Guillermo 2021-07-12 18:12:33 +02:00 committed by bernat
parent 4aae9ebd88
commit fc98625861
2 changed files with 70 additions and 63 deletions

View File

@ -31,38 +31,49 @@ class BasicAgent(object):
It has several functions available to specify the route that the agent must follow It has several functions available to specify the route that the agent must follow
""" """
def __init__(self, vehicle, target_speed=20, debug=False): def __init__(self, vehicle, target_speed=20, opt_dict={}):
""" """
:param vehicle: actor to apply to local planner logic onto :param vehicle: actor to apply to local planner logic onto
:param target_speed: speed (in Km/h) at which the vehicle will move :param target_speed: speed (in Km/h) at which the vehicle will move
:param opt_dict: dictionary in case some of its parameters want to be changed.
This also applies to parameters related to the LocalPlanner.
""" """
self._vehicle = vehicle self._vehicle = vehicle
self._world = self._vehicle.get_world() self._world = self._vehicle.get_world()
self._map = self._world.get_map() self._map = self._world.get_map()
self._debug = debug self._state = AgentState.NAVIGATING
# Base values
self._ignore_traffic_lights = False self._ignore_traffic_lights = False
self._ignore_stop_signs = False self._ignore_stop_signs = False
self._ignore_vehicles = False self._ignore_vehicles = False
self._last_traffic_light = None self._last_traffic_light = None
self._state = AgentState.NAVIGATING
self._target_speed = target_speed self._target_speed = target_speed
self._sampling_resolution = 2.0 self._sampling_resolution = 2.0
self._global_planner = GlobalRoutePlanner(self._map, self._sampling_resolution)
self._base_tlight_threshold = 5.0 # meters self._base_tlight_threshold = 5.0 # meters
self._base_vehicle_threshold = 5.0 # meters self._base_vehicle_threshold = 5.0 # meters
self._max_brake = 0.5 self._max_brake = 0.5
self._max_steering = 0.5
self._local_planner = LocalPlanner( # Change values according to the target speed
self._vehicle, opt_dict['target_speed'] = target_speed
opt_dict={ if 'ignore_traffic_lights' in opt_dict:
'target_speed' : target_speed, self._ignore_traffic_lights = opt_dict['ignore_traffic_lights']
'max_brake': self._max_brake, if 'ignore_stop_signs' in opt_dict:
'max_steering': self._max_steering self._ignore_stop_signs = opt_dict['ignore_stop_signs']
} if 'ignore_vehicles' in opt_dict:
) self._ignore_vehicles = opt_dict['ignore_vehicles']
if 'sampling_resolution' in opt_dict:
self._sampling_resolution = opt_dict['sampling_resolution']
if 'base_tlight_threshold' in opt_dict:
self._base_tlight_threshold = opt_dict['base_tlight_threshold']
if 'base_vehicle_threshold' in opt_dict:
self._base_vehicle_threshold = opt_dict['base_vehicle_threshold']
if 'max_brake' in opt_dict:
self._max_steering = opt_dict['max_brake']
# Initialize the planners
self._local_planner = LocalPlanner(self._vehicle, opt_dict=opt_dict)
self._global_planner = GlobalRoutePlanner(self._map, self._sampling_resolution)
def add_emergency_stop(self, control): def add_emergency_stop(self, control):
""" """
@ -119,22 +130,22 @@ class BasicAgent(object):
route_trace = self.trace_route(start_waypoint, end_waypoint) route_trace = self.trace_route(start_waypoint, end_waypoint)
self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue) self._local_planner.set_global_plan(route_trace, clean_queue=clean_queue)
for i, w in enumerate(route_trace): # for i, w in enumerate(route_trace):
wp = w[0].transform.location + carla.Location(z=0.1) # wp = w[0].transform.location + carla.Location(z=0.1)
if w[1] == RoadOption.LEFT: # Yellow # if w[1] == RoadOption.LEFT: # Yellow
color = carla.Color(255, 255, 0) # color = carla.Color(255, 255, 0)
elif w[1] == RoadOption.RIGHT: # Cyan # elif w[1] == RoadOption.RIGHT: # Cyan
color = carla.Color(0, 255, 255) # color = carla.Color(0, 255, 255)
elif w[1] == RoadOption.CHANGELANELEFT: # Orange # elif w[1] == RoadOption.CHANGELANELEFT: # Orange
color = carla.Color(255, 64, 0) # color = carla.Color(255, 64, 0)
elif w[1] == RoadOption.CHANGELANERIGHT: # Dark Cyan # elif w[1] == RoadOption.CHANGELANERIGHT: # Dark Cyan
color = carla.Color(0, 64, 255) # color = carla.Color(0, 64, 255)
elif w[1] == RoadOption.STRAIGHT: # Gray # elif w[1] == RoadOption.STRAIGHT: # Gray
color = carla.Color(128, 128, 128) # color = carla.Color(128, 128, 128)
else: # LANEFOLLOW # else: # LANEFOLLOW
color = carla.Color(0, 255, 0) # Green # color = carla.Color(0, 255, 0) # Green
self._world.debug.draw_point(wp, size=0.08, color=color, life_time=100) # self._world.debug.draw_point(wp, size=0.08, color=color, life_time=100)
self._world.debug.draw_string(wp, str(i), color=color, life_time=100) # self._world.debug.draw_string(wp, str(i), color=color, life_time=100)
def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True): def set_global_plan(self, plan, stop_waypoint_creation=True, clean_queue=True):
""" """
@ -313,6 +324,8 @@ class BasicAgent(object):
target_wpt = self._map.get_waypoint(target_transform.location) target_wpt = self._map.get_waypoint(target_transform.location)
if target_wpt.road_id != ego_wpt.road_id or target_wpt.lane_id != ego_wpt.lane_id: if target_wpt.road_id != ego_wpt.road_id or target_wpt.lane_id != ego_wpt.lane_id:
next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=3)[0] next_wpt = self._local_planner.get_incoming_waypoint_and_direction(steps=3)[0]
if not next_wpt:
continue
if target_wpt.road_id != next_wpt.road_id or target_wpt.lane_id != next_wpt.lane_id: if target_wpt.road_id != next_wpt.road_id or target_wpt.lane_id != next_wpt.lane_id:
continue continue

View File

@ -58,43 +58,28 @@ class LocalPlanner(object):
self._world = self._vehicle.get_world() self._world = self._vehicle.get_world()
self._map = self._world.get_map() self._map = self._world.get_map()
self._target_speed = 20.0 # Km/h
self._sampling_radius = 2.0
self._base_min_distance = 3.0
self._dt = 1.0 / 20.0
self._max_brake = 0.3
self._max_throt = 0.75
self._max_steer = 0.8
self._offset = 0
self._args_lateral_dict = {'K_P': 1.95, 'K_D': 0.2, 'K_I': 0.05, 'dt': self._dt}
self._args_longitudinal_dict = {'K_P': 1.0, 'K_D': 0, 'K_I': 0.05, 'dt': self._dt}
self._vehicle_controller = None self._vehicle_controller = None
self.target_waypoint = None self.target_waypoint = None
self.target_road_option = None self.target_road_option = None
self._waypoints_queue = deque(maxlen=10000) self._waypoints_queue = deque(maxlen=10000)
self._min_waypoint_queue_length = 100 self._min_waypoint_queue_length = 100
self._stop_waypoint_creation = False self._stop_waypoint_creation = False
# Base parameters
self._dt = 1.0 / 20.0
self._target_speed = 20.0 # Km/h
self._sampling_radius = 2.0
self._args_lateral_dict = {'K_P': 1.95, 'K_D': 0.2, 'K_I': 0.05, 'dt': self._dt}
self._args_longitudinal_dict = {'K_P': 1.0, 'K_D': 0, 'K_I': 0.05, 'dt': self._dt}
self._max_throt = 0.75
self._max_brake = 0.3
self._max_steer = 0.8
self._offset = 0
self._base_min_distance = 3.0
self._follow_speed_limits = False self._follow_speed_limits = False
# initializing controller # Overload parameters
self._init_controller(opt_dict)
def reset_vehicle(self):
"""Reset the ego-vehicle"""
self._vehicle = None
def _init_controller(self, opt_dict):
"""
Controller initialization.
:param opt_dict: dictionary of arguments.
:return:
"""
# parameters overload
if opt_dict: if opt_dict:
if 'dt' in opt_dict: if 'dt' in opt_dict:
self._dt = opt_dict['dt'] self._dt = opt_dict['dt']
@ -114,7 +99,20 @@ class LocalPlanner(object):
self._max_steer = opt_dict['max_steering'] self._max_steer = opt_dict['max_steering']
if 'offset' in opt_dict: if 'offset' in opt_dict:
self._offset = opt_dict['offset'] self._offset = opt_dict['offset']
if 'base_min_distance' in opt_dict:
self._base_min_distance = opt_dict['base_min_distance']
if 'follow_speed_limits' in opt_dict:
self._follow_speed_limits = opt_dict['follow_speed_limits']
# initializing controller
self._init_controller()
def reset_vehicle(self):
"""Reset the ego-vehicle"""
self._vehicle = None
def _init_controller(self):
"""Controller initialization"""
self._vehicle_controller = VehiclePIDController(self._vehicle, self._vehicle_controller = VehiclePIDController(self._vehicle,
args_lateral=self._args_lateral_dict, args_lateral=self._args_lateral_dict,
args_longitudinal=self._args_longitudinal_dict, args_longitudinal=self._args_longitudinal_dict,
@ -128,7 +126,6 @@ class LocalPlanner(object):
self.target_waypoint, self.target_road_option = (current_waypoint, RoadOption.LANEFOLLOW) self.target_waypoint, self.target_road_option = (current_waypoint, RoadOption.LANEFOLLOW)
self._waypoints_queue.append((self.target_waypoint, self.target_road_option)) self._waypoints_queue.append((self.target_waypoint, self.target_road_option))
def set_speed(self, speed): def set_speed(self, speed):
""" """
Changes the target speed Changes the target speed
@ -141,7 +138,6 @@ class LocalPlanner(object):
"Use 'follow_speed_limits' to deactivate this") "Use 'follow_speed_limits' to deactivate this")
self._target_speed = speed self._target_speed = speed
def follow_speed_limits(self, value=True): def follow_speed_limits(self, value=True):
""" """
Activates a flag that makes the max speed dynamically vary according to the spped limits Activates a flag that makes the max speed dynamically vary according to the spped limits
@ -151,7 +147,6 @@ class LocalPlanner(object):
""" """
self._follow_speed_limits = value self._follow_speed_limits = value
def _compute_next_waypoints(self, k=1): def _compute_next_waypoints(self, k=1):
""" """
Add new waypoints to the trajectory queue. Add new waypoints to the trajectory queue.
@ -183,7 +178,6 @@ class LocalPlanner(object):
self._waypoints_queue.append((next_waypoint, road_option)) self._waypoints_queue.append((next_waypoint, road_option))
def set_global_plan(self, current_plan, stop_waypoint_creation=True, clean_queue=True): def set_global_plan(self, current_plan, stop_waypoint_creation=True, clean_queue=True):
""" """
Adds a new plan to the local planner. A plan must be a list of [carla.Waypoint, RoadOption] pairs Adds a new plan to the local planner. A plan must be a list of [carla.Waypoint, RoadOption] pairs