Skip to content

Commit

Permalink
added functionality to allow spawn of random traffic and spawn of con…
Browse files Browse the repository at this point in the history
…trollable vehicles
  • Loading branch information
enrique committed Sep 29, 2023
1 parent a1eb105 commit c73cce2
Show file tree
Hide file tree
Showing 7 changed files with 49 additions and 11 deletions.
Binary file removed assets/behavior_metrics_full_architecture.png
Binary file not shown.
Original file line number Diff line number Diff line change
Expand Up @@ -77,7 +77,10 @@ def __init__(self, sensors, actuators, handler, model, config=None):
self.world.unload_map_layer(carla.MapLayer.Particles)

time.sleep(5)
self.vehicle = self.world.get_actors().filter('vehicle.*')[0]
self.vehicle = next(
(p for p in self.world.get_actors() if 'vehicle' in p.type_id and p.attributes.get('role_name') == 'ego_vehicle'),
None
)

if model:
if not path.exists(PRETRAINED_MODELS + model):
Expand Down Expand Up @@ -195,7 +198,7 @@ def execute(self):
self.motors.sendThrottle(throttle)
self.motors.sendSteer(steer)
self.motors.sendBrake(break_command)

if vehicle_speed >= 35:
self.motors.sendThrottle(0.0)
self.motors.sendBrake(0.0)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -156,6 +156,22 @@
"id": "control"
}
]
},
{
"type": "vehicle.audi.a2",
"id": "npc_vehicle_1",
"spawn_point": {"x": 60.0, "y": 2.0, "z": 1.37, "roll": 0.0, "pitch": 0.0, "yaw": 180.0},
"sensors":
[
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.odom",
"id": "odometry"
}
]
}
]
}
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@
<!--<arg name="spawn_point" default="-7.0, -120.6, 1.37, 0.0, 0.0, -90.0"/>-->
<!--<arg name="spawn_point" default="-7.0, -270.6, 1.37, 0.0, 0.0, -90.0"/>-->

<arg name="spawn_point" default="10.0, -307.0, 1.37, 0.0, 0.0, 0.0"/>
<!--<arg name="spawn_point" default="10.0, -307.0, 1.37, 0.0, 0.0, 0.0"/>-->
<!--<arg name="spawn_point" default="100.0, -307.0, 1.37, 0.0, 0.0, 0.0"/>-->
<!--<arg name="spawn_point" default="150.0, -307.0, 1.37, 0.0, 0.0, 0.0"/>-->

Expand Down Expand Up @@ -62,13 +62,20 @@
<arg name='fixed_delta_seconds' value='$(arg fixed_delta_seconds)'/>
</include>

<!-- the ego vehicle, that will be controlled by an agent (e.g. carla_ad_agent) -->
<include file="$(find carla_spawn_objects)/launch/carla_example_ego_vehicle.launch">
<arg name="objects_definition_file" value='$(find carla_spawn_objects)/config/objects.json'/>
<arg name='role_name' value='$(arg role_name)'/>
<arg name="spawn_point_ego_vehicle" value="$(arg spawn_point)"/>
<arg name="spawn_sensors_only" value="false"/>
</include>
<arg name="objects_definition_file" default='$(env OBJECT_PATH)/main_car.json'/>

<arg name='ego_vehicle_role_name' default='ego_vehicle'/>
<arg name="ego_spawn_point" default="150.3, -307.0, 1.37, 0.0, 0.0, 0.0"/>
<arg name='npc_1_role_name' default='npc_vehicle_1'/>
<arg name="npc_1_spawn_point" default="194.0, -285.0, 1.37, 0.0, 0.0, 90.0"/>

<!-- spawn the objects -->
<node pkg="carla_spawn_objects" type="carla_spawn_objects.py" name="$(anon carla_spawn_objects)" output="screen">
<param name="spawn_point_$(arg ego_vehicle_role_name)" value="$(arg ego_spawn_point)"/>
<param name="objects_definition_file" value="$(arg objects_definition_file)"/>
<param name="spawn_point_$(arg npc_1_role_name)" value="$(arg npc_1_spawn_point)" />
<param name="spawn_sensors_only" value="false"/>
</node>

<include file="$(find carla_manual_control)/launch/carla_manual_control.launch">
<arg name='role_name' value='$(arg role_name)'/>
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -49,6 +49,7 @@ Behaviors:
Simulation:
World: configs/CARLA/CARLA_launch_files/town_02_anticlockwise_low.launch
RandomSpawnPoint: False
MultiCar: True
Dataset:
In: '/tmp/my_bag.bag'
Out: ''
Expand Down
5 changes: 5 additions & 0 deletions behavior_metrics/utils/configuration.py
Original file line number Diff line number Diff line change
Expand Up @@ -141,6 +141,11 @@ def initialize_configuration(self, config_data):
else:
self.spawn_points = []

if 'MultiCar' in config_data['Behaviors']['Simulation']:
self.multicar = config_data['Behaviors']['Simulation']['MultiCar']
else:
self.multicar = False

if 'NumberOfVehicle' in config_data['Behaviors']['Simulation']:
self.number_of_vehicle = config_data['Behaviors']['Simulation']['NumberOfVehicle']
else:
Expand Down
8 changes: 7 additions & 1 deletion behavior_metrics/utils/traffic.py
Original file line number Diff line number Diff line change
Expand Up @@ -34,6 +34,11 @@ def __init__(self, n_vehicle, n_walker, percentage_walker_running=0.0, percentag
self.walker_ids = []

def generate_traffic(self):
for p in self.world.get_actors():
if 'vehicle' in p.type_id:
if p.attributes['role_name'] != 'ego_vehicle':
set_autopilot(p, True, self.traffic_manager.get_port())

if self.n_vehicle > 0:
self.spawn_vehicles(self.world, self.client, self.n_vehicle, self.traffic_manager)
if self.n_walker > 0:
Expand Down Expand Up @@ -105,7 +110,8 @@ def spawn_vehicles(self, world, client, n_vehicles, traffic_manager):
if blueprint.has_attribute('driver_id'):
driver_id = random.choice(blueprint.get_attribute('driver_id').recommended_values)
blueprint.set_attribute('driver_id', driver_id)
blueprint.set_attribute('role_name', 'autopilot')
blueprint.set_attribute('role_name', 'npc_vehicle_1')


batch.append(spawn_actor(blueprint, transform)
.then(set_autopilot(future_actor, True, traffic_manager.get_port())))
Expand Down

0 comments on commit c73cce2

Please sign in to comment.