Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

First approach for Carla Simulator support #403

Merged
merged 38 commits into from
Dec 12, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
Show all changes
38 commits
Select commit Hold shift + click to select a range
ebfb62e
Added current scripts for running CARLA
Nov 16, 2022
6ac7cc3
Save total distance and time for simulation
Nov 16, 2022
763c45d
Connection between CARLA and ROS using ROS BRIDGE toy example!
Nov 17, 2022
10ae989
[WIP] Launch both CARLA and Behavior Metrics GUI
Nov 17, 2022
a9cdc0c
Launch CARLA and run first brain from config file
Nov 18, 2022
ac31025
Launch CARLA and run first brain from config file
sergiopaniego Nov 18, 2022
e3a5010
Merge branch 'issue-401' of https://github.com/JdeRobot/BehaviorMetri…
Nov 18, 2022
84c0940
Close all processes on finish
sergiopaniego Nov 18, 2022
fadf52d
Cameras working
sergiopaniego Nov 18, 2022
8e3b9af
Odometry working for CARLA
sergiopaniego Nov 18, 2022
e6a52bf
Steering added to motors
sergiopaniego Nov 18, 2022
c059ff1
Bird Eye View support added
sergiopaniego Nov 21, 2022
3fdc42b
Added initial metrics to CARLA
sergiopaniego Nov 21, 2022
e423df4
Added example launch file and updated config
sergiopaniego Nov 21, 2022
125b1ee
Added CARLA brain with neural network
sergiopaniego Nov 21, 2022
38736a4
Updated parameter in motors for CARLA
sergiopaniego Nov 28, 2022
ca8b734
Driver for CARLA working
sergiopaniego Nov 30, 2022
e08523f
Add padding to visualizations
sergiopaniego Nov 30, 2022
736fd3e
Added callbacks for lane invasion and collisions
sergiopaniego Nov 30, 2022
e592507
Metrics for lane invasion and collisions
sergiopaniego Nov 30, 2022
5b5a265
Added brake command for CARLA motors
sergiopaniego Nov 30, 2022
5ed6077
Play/pause and CARLA logo
sergiopaniego Nov 30, 2022
04332a7
Remove some Gazebo logs appearing in CARLA env
sergiopaniego Nov 30, 2022
2b631ac
Launch CARLA server and client directly
sergiopaniego Dec 2, 2022
d49f9d6
Launch files for different CARLA towns
sergiopaniego Dec 5, 2022
056ee27
Added config for Town03 launch
sergiopaniego Dec 5, 2022
92cf384
Added map launchs without gui for headless launch
sergiopaniego Dec 5, 2022
4971218
First approach for multiple and headless CARLA experiments
sergiopaniego Dec 5, 2022
f13183a
CARLA multiple experiments without GUI
sergiopaniego Dec 5, 2022
db60cc6
[WIP] Launch multifiles for CARLA as separate python processes
sergiopaniego Dec 9, 2022
40038c3
Launch CARLA multiple times without GUI
sergiopaniego Dec 9, 2022
5145f47
Renamed classes and files for Gazebo and Carla
sergiopaniego Dec 12, 2022
55b800f
Reviewed metrics calculation for Carla
sergiopaniego Dec 12, 2022
9b6bbc5
Driver carla without sleep
sergiopaniego Dec 12, 2022
39c21c2
Requirements for CARLA support
sergiopaniego Dec 12, 2022
980d1f6
Merge branch 'noetic-devel' of https://github.com/JdeRobot/BehaviorMe…
sergiopaniego Dec 12, 2022
eceb5f9
Updated requirements
sergiopaniego Dec 12, 2022
2e1a085
Removed unneeded folder
sergiopaniego Dec 12, 2022
File filter

Filter by extension

Filter by extension


Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
94 changes: 94 additions & 0 deletions behavior_metrics/brains/CARLA/brain_carla_autopilot.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
#!/usr/bin/python
# -*- coding: utf-8 -*-
import csv
import cv2
import math
import numpy as np
import threading
import time
import carla
from albumentations import (
Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare
)
from utils.constants import DATASETS_DIR, ROOT_PATH



GENERATED_DATASETS_DIR = ROOT_PATH + '/' + DATASETS_DIR


class Brain:

def __init__(self, sensors, actuators, handler, config=None):
self.camera = sensors.get_camera('camera_0')
self.camera_1 = sensors.get_camera('camera_1')
self.camera_2 = sensors.get_camera('camera_2')
self.camera_3 = sensors.get_camera('camera_3')

self.pose = sensors.get_pose3d('pose3d_0')

self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0')

self.motors = actuators.get_motor('motors_0')
self.handler = handler
self.config = config

self.threshold_image = np.zeros((640, 360, 3), np.uint8)
self.color_image = np.zeros((640, 360, 3), np.uint8)
self.lock = threading.Lock()
self.threshold_image_lock = threading.Lock()
self.color_image_lock = threading.Lock()
self.cont = 0
self.iteration = 0

# self.previous_timestamp = 0
# self.previous_image = 0

self.previous_v = None
self.previous_w = None
self.previous_w_normalized = None
self.suddenness_distance = []

client = carla.Client('localhost', 2000)
client.set_timeout(10.0) # seconds
world = client.get_world()
time.sleep(3)
self.vehicle = world.get_actors().filter('vehicle.*')[0]

time.sleep(2)

def update_frame(self, frame_id, data):
"""Update the information to be shown in one of the GUI's frames.

Arguments:
frame_id {str} -- Id of the frame that will represent the data
data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
"""
self.handler.update_frame(frame_id, data)

def update_pose(self, pose_data):
self.handler.update_pose3d(pose_data)

def execute(self):
image = self.camera.getImage().data
image_1 = self.camera_1.getImage().data
image_2 = self.camera_2.getImage().data
image_3 = self.camera_3.getImage().data

bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle)

#print(self.bird_eye_view.getImage(self.vehicle))

#self.motors.sendW(w)
self.motors.sendV(1)
self.update_frame('frame_0', image)
self.update_frame('frame_1', image_1)
self.update_frame('frame_2', image_2)
self.update_frame('frame_3', image_3)

#self.update_frame('frame_0', bird_eye_view_1)


self.update_pose(self.pose.getPose3d())
#print(self.pose.getPose3d())

151 changes: 151 additions & 0 deletions behavior_metrics/brains/CARLA/brain_carla_bird_eye_deep_learning.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,151 @@
#!/usr/bin/python
# -*- coding: utf-8 -*-
import csv
import cv2
import math
import numpy as np
import threading
import time
import carla
from albumentations import (
Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare
)
from utils.constants import DATASETS_DIR, ROOT_PATH

import tensorflow as tf
gpus = tf.config.experimental.list_physical_devices('GPU')
for gpu in gpus:
tf.config.experimental.set_memory_growth(gpu, True)

PRETRAINED_MODELS = "../models/"

class Brain:

def __init__(self, sensors, actuators, handler, config=None):
self.camera = sensors.get_camera('camera_0')
self.camera_1 = sensors.get_camera('camera_1')
self.camera_2 = sensors.get_camera('camera_2')
self.camera_3 = sensors.get_camera('camera_3')

self.pose = sensors.get_pose3d('pose3d_0')

self.bird_eye_view = sensors.get_bird_eye_view('bird_eye_view_0')

self.motors = actuators.get_motor('motors_0')
self.handler = handler
self.config = config

self.threshold_image = np.zeros((640, 360, 3), np.uint8)
self.color_image = np.zeros((640, 360, 3), np.uint8)
'''
self.lock = threading.Lock()
self.threshold_image_lock = threading.Lock()
self.color_image_lock = threading.Lock()
'''
self.cont = 0
self.iteration = 0

# self.previous_timestamp = 0
# self.previous_image = 0

self.previous_v = None
self.previous_w = None
self.previous_w_normalized = None
self.suddenness_distance = []

client = carla.Client('localhost', 2000)
client.set_timeout(10.0) # seconds
world = client.get_world()
time.sleep(10)
#print(world.get_actors())
self.vehicle = world.get_actors().filter('vehicle.*')[0]

model = '/home/jderobot/Documents/Projects/BehaviorMetrics/PlayingWithCARLA/models/20221104-143528_pilotnet_CARLA_17_10_dataset_bird_eye_300_epochs_no_flip_3_output_velocity_all_towns_vel_30_cp.h5'
self.net = tf.keras.models.load_model(model)
self.previous_speed = 0


def update_frame(self, frame_id, data):
"""Update the information to be shown in one of the GUI's frames.

Arguments:
frame_id {str} -- Id of the frame that will represent the data
data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
"""
if data.shape[0] != data.shape[1]:
if data.shape[0] > data.shape[1]:
difference = data.shape[0] - data.shape[1]
extra_left, extra_right = int(difference/2), int(difference/2)
extra_top, extra_bottom = 0, 0
else:
difference = data.shape[1] - data.shape[0]
extra_left, extra_right = 0, 0
extra_top, extra_bottom = int(difference/2), int(difference/2)


data = np.pad(data, ((extra_top, extra_bottom), (extra_left, extra_right), (0, 0)), mode='constant', constant_values=0)

self.handler.update_frame(frame_id, data)

def update_pose(self, pose_data):
self.handler.update_pose3d(pose_data)

def execute(self):
#print(self.vehicle.get_location())
image = self.camera.getImage().data
image_1 = self.camera_1.getImage().data
image_2 = self.camera_2.getImage().data
image_3 = self.camera_3.getImage().data

bird_eye_view_1 = self.bird_eye_view.getImage(self.vehicle)

#print(self.bird_eye_view.getImage(self.vehicle))

#self.update_frame('frame_0', image)
self.update_frame('frame_1', image_1)
self.update_frame('frame_2', image_2)
self.update_frame('frame_3', image_3)

self.update_frame('frame_0', bird_eye_view_1)

self.update_pose(self.pose.getPose3d())

image_shape=(50, 150)
img_base = cv2.resize(bird_eye_view_1, image_shape)

AUGMENTATIONS_TEST = Compose([
Normalize()
])
image = AUGMENTATIONS_TEST(image=img_base)
img = image["image"]

#velocity_dim = np.full((150, 50), 0.5)
velocity_dim = np.full((150, 50), self.previous_speed/30)
new_img_vel = np.dstack((img, velocity_dim))
img = new_img_vel

img = np.expand_dims(img, axis=0)
prediction = self.net.predict(img, verbose=0)
throttle = prediction[0][0]
steer = prediction[0][1] * (1 - (-1)) + (-1)
break_command = prediction[0][2]
speed = self.vehicle.get_velocity()
vehicle_speed = 3.6 * math.sqrt(speed.x**2 + speed.y**2 + speed.z**2)
self.previous_speed = vehicle_speed

if vehicle_speed > 300:
self.motors.sendThrottle(0)
self.motors.sendSteer(steer)
self.motors.sendBrake(0)
else:
if vehicle_speed < 2:
self.motors.sendThrottle(1.0)
self.motors.sendSteer(0.0)
self.motors.sendBrake(0)
else:
self.motors.sendThrottle(throttle)
self.motors.sendSteer(steer)
self.motors.sendBrake(0)



76 changes: 76 additions & 0 deletions behavior_metrics/brains/CARLA/brain_carla_slow_and_turn.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,76 @@
#!/usr/bin/python
# -*- coding: utf-8 -*-
import csv
import cv2
import math
import numpy as np
import threading
import time
from albumentations import (
Compose, Normalize, RandomRain, RandomBrightness, RandomShadow, RandomSnow, RandomFog, RandomSunFlare
)
from utils.constants import DATASETS_DIR, ROOT_PATH



GENERATED_DATASETS_DIR = ROOT_PATH + '/' + DATASETS_DIR


class Brain:

def __init__(self, sensors, actuators, handler, config=None):
self.camera = sensors.get_camera('camera_0')
self.camera_1 = sensors.get_camera('camera_1')
self.camera_2 = sensors.get_camera('camera_2')
self.camera_3 = sensors.get_camera('camera_3')

self.pose = sensors.get_pose3d('pose3d_0')

self.motors = actuators.get_motor('motors_0')
self.handler = handler
self.config = config

self.threshold_image = np.zeros((640, 360, 3), np.uint8)
self.color_image = np.zeros((640, 360, 3), np.uint8)
self.lock = threading.Lock()
self.threshold_image_lock = threading.Lock()
self.color_image_lock = threading.Lock()
self.cont = 0
self.iteration = 0

# self.previous_timestamp = 0
# self.previous_image = 0

self.previous_v = None
self.previous_w = None
self.previous_w_normalized = None
self.suddenness_distance = []

time.sleep(2)

def update_frame(self, frame_id, data):
"""Update the information to be shown in one of the GUI's frames.

Arguments:
frame_id {str} -- Id of the frame that will represent the data
data {*} -- Data to be shown in the frame. Depending on the type of frame (rgbimage, laser, pose3d, etc)
"""
self.handler.update_frame(frame_id, data)

def update_pose(self, pose_data):
self.handler.update_pose3d(pose_data)

def execute(self):
image = self.camera.getImage().data
image_1 = self.camera_1.getImage().data
image_2 = self.camera_2.getImage().data
image_3 = self.camera_3.getImage().data

self.motors.sendW(1)
self.motors.sendV(0.5)
self.update_frame('frame_0', image)
self.update_frame('frame_1', image_1)
self.update_frame('frame_2', image_2)
self.update_frame('frame_3', image_3)
self.update_pose(self.pose.getPose3d())
#print(self.pose.getPose3d())
6 changes: 5 additions & 1 deletion behavior_metrics/brains/brains_handler.py
Original file line number Diff line number Diff line change
Expand Up @@ -39,8 +39,12 @@ def load_brain(self, path, model=None):

if robot_type == 'f1rl':
from utils import environment
environment.close_gazebo()
environment.close_ros_and_simulators()
exec(open(self.brain_path).read())
elif robot_type == 'CARLA':
module = importlib.import_module(import_name)
Brain = getattr(module, 'Brain')
self.active_brain = Brain(self.sensors, self.actuators, handler=self, config=self.config)
else:
if import_name in sys.modules: # for reloading sake
del sys.modules[import_name]
Expand Down
49 changes: 49 additions & 0 deletions behavior_metrics/configs/CARLA_launch_files/town_01.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
<!-- -->
<launch>
<!-- CARLA connection -->
<arg name='host' default='localhost'/>
<arg name='port' default='2000'/>
<arg name='timeout' default='10'/>

<!-- Ego vehicle -->
<arg name='role_name' default='ego_vehicle'/>
<arg name="vehicle_filter" default='vehicle.*'/>
<!--<arg name="spawn_point" default=""/>--><!-- use comma separated format "x,y,z,roll,pitch,yaw" -->
<arg name="spawn_point" default="40.0, 2.0, 1.37, 0.0, 0.0, 180.0"/>
<!--<arg name="spawn_point" default="-2.0, -10.0, 1.37, 0.0, 0.0, -90.0"/>-->
<!--<arg name="spawn_point" default="-2.0, -280.0, 1.37, 0.0, 0.0, -90.0"/>-->

<!-- Map to load on startup (either a predefined CARLA town (e.g. 'Town01'), or a OpenDRIVE map file) -->
<arg name="town" default='Town01'/>

<!-- Enable/disable passive mode -->
<arg name='passive' default=''/>

<!-- Synchronous mode-->
<arg name='synchronous_mode_wait_for_vehicle_control_command' default='False'/>
<arg name='fixed_delta_seconds' default='0.05'/>


<include file="$(find carla_ros_bridge)/launch/carla_ros_bridge.launch">
<arg name='host' value='$(arg host)'/>
<arg name='port' value='$(arg port)'/>
<arg name='town' value='$(arg town)'/>
<arg name='timeout' value='$(arg timeout)'/>
<arg name='passive' value='$(arg passive)'/>
<arg name='synchronous_mode_wait_for_vehicle_control_command' value='$(arg synchronous_mode_wait_for_vehicle_control_command)'/>
<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>

<include file="$(find carla_manual_control)/launch/carla_manual_control.launch">
<arg name='role_name' value='$(arg role_name)'/>
</include>

</launch>
Loading