Skip to content

Commit

Permalink
Merge pull request #639 from YujiroS/carla_subjective_vision
Browse files Browse the repository at this point in the history
Add a metric that retrieves the distance to the front vehicle
  • Loading branch information
sergiopaniego authored Oct 3, 2023
2 parents 86171a1 + 2a44f27 commit 340c740
Show file tree
Hide file tree
Showing 20 changed files with 614 additions and 101 deletions.
2 changes: 1 addition & 1 deletion README.md
Original file line number Diff line number Diff line change
Expand Up @@ -84,4 +84,4 @@ The robot controller (brain folder) is the main controller of the ego vehicle.

Behavior Metrics uses a publish/subscribe design to communicate with the simulator

![alt text](./assets/behavior_metrics_publish_subscribe.png)
![alt text](./assets/behavior_metrics_publish_subscribe.png)
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 @@ -124,7 +127,7 @@ def execute(self):
image_2 = self.camera_2.getImage().data
image_3 = self.camera_3.getImage().data

cropped = image[230:-1,:]
cropped = image[200:-1,:]
if self.cont < 20:
self.cont += 1

Expand Down Expand Up @@ -195,6 +198,10 @@ 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)

if self.previous_commanded_throttle != None:
a = np.array((throttle, steer, break_command))
Expand Down
1 change: 1 addition & 0 deletions behavior_metrics/carla-birdeye-view
Submodule carla-birdeye-view added at 9f4255
Original file line number Diff line number Diff line change
@@ -0,0 +1,177 @@
{
"objects":
[
{
"type": "sensor.pseudo.traffic_lights",
"id": "traffic_lights"
},
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.actor_list",
"id": "actor_list"
},
{
"type": "sensor.pseudo.markers",
"id": "markers"
},
{
"type": "sensor.pseudo.opendrive_map",
"id": "map"
},
{
"type": "vehicle.tesla.model3",
"id": "ego_vehicle",
"sensors":
[
{
"type": "sensor.camera.rgb",
"id": "rgb_front",
"spawn_point": {"x": 2.5, "y": 0.0, "z": 0.8, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"image_size_x": 640,
"image_size_y": 480
},
{
"type": "sensor.camera.rgb",
"id": "rgb_view",
"spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 90.0,
"attached_objects":
[
{
"type": "actor.pseudo.control",
"id": "control"
}
]
},
{
"type": "sensor.lidar.ray_cast",
"id": "lidar",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"range": 50,
"channels": 32,
"points_per_second": 320000,
"upper_fov": 2.0,
"lower_fov": -26.8,
"rotation_frequency": 20,
"noise_stddev": 0.0
},
{
"type": "sensor.lidar.ray_cast_semantic",
"id": "semantic_lidar",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"range": 50,
"channels": 32,
"points_per_second": 320000,
"upper_fov": 2.0,
"lower_fov": -26.8,
"rotation_frequency": 20
},
{
"type": "sensor.other.radar",
"id": "radar_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"horizontal_fov": 30.0,
"vertical_fov": 10.0,
"points_per_second": 1500,
"range": 100.0
},
{
"type": "sensor.camera.semantic_segmentation",
"id": "semantic_segmentation_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70
},
{
"type": "sensor.camera.depth",
"id": "depth_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70
},
{
"type": "sensor.camera.dvs",
"id": "dvs_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70,
"positive_threshold": 0.3,
"negative_threshold": 0.3,
"sigma_positive_threshold": 0.0,
"sigma_negative_threshold": 0.0,
"use_log": true,
"log_eps": 0.001
},
{
"type": "sensor.other.gnss",
"id": "gnss",
"spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
"noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
"noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
},
{
"type": "sensor.other.imu",
"id": "imu",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
"noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
"noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
},
{
"type": "sensor.other.collision",
"id": "collision",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
},
{
"type": "sensor.other.lane_invasion",
"id": "lane_invasion",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
},
{
"type": "sensor.pseudo.tf",
"id": "tf"
},
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.odom",
"id": "odometry"
},
{
"type": "sensor.pseudo.speedometer",
"id": "speedometer"
},
{
"type": "actor.pseudo.control",
"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
@@ -0,0 +1,178 @@
{
"objects":
[
{
"type": "sensor.pseudo.traffic_lights",
"id": "traffic_lights"
},
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.actor_list",
"id": "actor_list"
},
{
"type": "sensor.pseudo.markers",
"id": "markers"
},
{
"type": "sensor.pseudo.opendrive_map",
"id": "map"
},
{
"type": "vehicle.tesla.model3",
"id": "ego_vehicle",
"sensors":
[
{
"type": "sensor.camera.rgb",
"id": "rgb_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 90.0
},
{
"type": "sensor.camera.rgb",
"id": "rgb_view",
"spawn_point": {"x": -4.5, "y": 0.0, "z": 2.8, "roll": 0.0, "pitch": 20.0, "yaw": 0.0},
"image_size_x": 800,
"image_size_y": 600,
"fov": 90.0,
"attached_objects":
[
{
"type": "actor.pseudo.control",
"id": "control"
}
]
},
{
"type": "sensor.lidar.ray_cast",
"id": "lidar",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"range": 50,
"channels": 32,
"points_per_second": 320000,
"upper_fov": 2.0,
"lower_fov": -26.8,
"rotation_frequency": 20,
"noise_stddev": 0.0
},
{
"type": "sensor.lidar.ray_cast_semantic",
"id": "semantic_lidar",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 2.4, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"range": 50,
"channels": 32,
"points_per_second": 320000,
"upper_fov": 2.0,
"lower_fov": -26.8,
"rotation_frequency": 20
},
{
"type": "sensor.other.radar",
"id": "radar_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"horizontal_fov": 30.0,
"vertical_fov": 10.0,
"points_per_second": 1500,
"range": 100.0
},
{
"type": "sensor.camera.semantic_segmentation",
"id": "semantic_segmentation_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70
},
{
"type": "sensor.camera.depth",
"id": "depth_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70
},
{
"type": "sensor.camera.dvs",
"id": "dvs_front",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"fov": 90.0,
"image_size_x": 400,
"image_size_y": 70,
"positive_threshold": 0.3,
"negative_threshold": 0.3,
"sigma_positive_threshold": 0.0,
"sigma_negative_threshold": 0.0,
"use_log": true,
"log_eps": 0.001
},
{
"type": "sensor.other.gnss",
"id": "gnss",
"spawn_point": {"x": 1.0, "y": 0.0, "z": 2.0},
"noise_alt_stddev": 0.0, "noise_lat_stddev": 0.0, "noise_lon_stddev": 0.0,
"noise_alt_bias": 0.0, "noise_lat_bias": 0.0, "noise_lon_bias": 0.0
},
{
"type": "sensor.other.imu",
"id": "imu",
"spawn_point": {"x": 2.0, "y": 0.0, "z": 2.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
"noise_accel_stddev_x": 0.0, "noise_accel_stddev_y": 0.0, "noise_accel_stddev_z": 0.0,
"noise_gyro_stddev_x": 0.0, "noise_gyro_stddev_y": 0.0, "noise_gyro_stddev_z": 0.0,
"noise_gyro_bias_x": 0.0, "noise_gyro_bias_y": 0.0, "noise_gyro_bias_z": 0.0
},
{
"type": "sensor.other.collision",
"id": "collision",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
},
{
"type": "sensor.other.lane_invasion",
"id": "lane_invasion",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0}
},
{
"type": "sensor.pseudo.tf",
"id": "tf"
},
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.odom",
"id": "odometry"
},
{
"type": "sensor.pseudo.speedometer",
"id": "speedometer"
},
{
"type": "actor.pseudo.control",
"id": "control"
}
]
},
{
"type": "vehicle.audi.a2",
"id": "npc_vehicle_1",
"spawn_point": {"x": 194.0, "y": -250, "z": 1.37, "roll": 0.0, "pitch": 0.0, "yaw": 90.0},
"sensors":
[
{
"type": "sensor.pseudo.objects",
"id": "objects"
},
{
"type": "sensor.pseudo.odom",
"id": "odometry"
}
]
}
]
}
Loading

0 comments on commit 340c740

Please sign in to comment.