Skip to content

Commit

Permalink
Include carla client in roslaunch
Browse files Browse the repository at this point in the history
- Use more realistic Velodyne parameters
- rework carla clients
  • Loading branch information
fred-labs committed Feb 19, 2019
1 parent f69b9d2 commit e0f870d
Show file tree
Hide file tree
Showing 20 changed files with 245 additions and 290 deletions.
44 changes: 3 additions & 41 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -70,7 +70,10 @@ You need two terminals:
#execute carla-autoware-bridge and carla-autoware-bridge
export PYTHONPATH=<path-to-carla>/PythonAPI/carla-<version_and_arch>.egg:<path-to-carla>/PythonAPI/
source $CARLA_AUTOWARE_ROOT/catkin_ws/devel/setup.bash
#either execute a headless Carla client
roslaunch carla_autoware_bridge carla_autoware_bridge.launch
#or
roslaunch carla_autoware_bridge carla_autoware_bridge_with_manual_control.launch

In Autoware Runtime Manager, select the customized launch files:

Expand All @@ -86,44 +89,3 @@ Now you can start the Autoware Stack by starting all launch files from top to bo
A special camera is positioned behind the car to see the car and its environment.
You can subscribe to it via ```/carla/ego_vehicle/camera/rgb/viewFromBehind/image_color```.

### Run with controllable Carla client

It is also possible to run a Carla client, that can additionally be controlled by keyboard.

The execution order:

1. Carla Server
2. Carla Client
3. Autoware Runtime Manager
4. Carla Autoware Bridge
5. Autoware Stack

You need three terminals:

#Terminal 1

#execute Carla
SDL_VIDEODRIVER=offscreen <path-to-carla>/CarlaUE4.sh /Game/Carla/Maps/Town01 -benchmark -fps=10


#Terminal 2

cd ~/carla-autoware

#execute Carla ego vehicle client
export PYTHONPATH=<path-to-carla>/PythonAPI/carla-<version_and_arch>.egg
./catkin_ws/src/carla_client/src/carla_autoware_manual_control.py --filter vehicle.toyota.prius*


#Terminal 3

export CARLA_AUTOWARE_ROOT=~/carla-autoware

#execute Autoware (forks into background)
<path-to-autoware>/ros/run

#execute carla-autoware-bridge and carla-autoware-bridge
export PYTHONPATH=<path-to-carla>/PythonAPI/carla-<version_and_arch>.egg:<path-to-carla>/PythonAPI/
source $CARLA_AUTOWARE_ROOT/catkin_ws/devel/setup.bash
roslaunch carla_autoware_bridge carla_autoware_bridge.launch

1 change: 1 addition & 0 deletions catkin_ws/.gitignore
Original file line number Diff line number Diff line change
Expand Up @@ -3,3 +3,4 @@ devel/
install/
src/CMakeLists.txt
.catkin_workspace
*.pyc
Original file line number Diff line number Diff line change
@@ -1,27 +1,9 @@
<launch>
<arg name="wheelbase" default="2.5" /> <!-- distance between front and back axle in meters -->

<!-- carla client -->
<include file="$(find carla_client)/launch/carla_client.launch" />

<include file="$(find carla_ros_bridge)/client.launch" />

<!-- remap carla lidar to autoware -->
<node pkg="topic_tools" type="relay" name="points_relay" args="/carla/ego_vehicle/lidar/sensor/point_cloud /points_raw"/>

<!-- remap carla front camera to autoware -->
<node pkg="topic_tools" type="relay" name="imag_relay" args="/carla/ego_vehicle/camera/rgb/front/image_color /image_raw"/>

<!-- extract pose from carla odometry -->
<node pkg="carla_autoware_bridge" type="odometry_to_posestamped" name="odometry_to_posestamped"/>

<!-- convert twist to carla ackermann drive-->
<node pkg="carla_autoware_bridge" type="vehiclecmd_to_ackermanndrive" name="vehiclecmd_to_ackermanndrive" output="screen">
<param name="wheelbase" value="$(arg wheelbase)"/>
</node>

<!-- mission planning -->
<include file="$(find carla_autoware_waypoint_publisher)/launch/carla_autoware_waypoint_publisher.launch" />
<!-- common -->
<include file="$(find carla_autoware_bridge)/launch/carla_autoware_bridge_common.launch" />

</launch>

Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
<launch>

<param name="/carla/client/start_in_autopilot" value="True" /> <!-- for capturing the pcl map, the autopilot drives around -->

<!-- carla client -->
<include file="$(find carla_client)/launch/carla_manual_client.launch" />

<!-- pcl map capturing -->
<include file="$(find pcl_recorder)/launch/pcl_recorder.launch" />

<!-- common -->
<include file="$(find carla_autoware_bridge)/launch/carla_autoware_bridge_common.launch" />

</launch>

Original file line number Diff line number Diff line change
@@ -0,0 +1,25 @@
<launch>
<arg name="wheelbase" default="2.5" /> <!-- distance between front and back axle in meters -->

<!-- ros bridge -->
<include file="$(find carla_ros_bridge)/client.launch" />

<!-- remap carla lidar to autoware -->
<node pkg="topic_tools" type="relay" name="points_relay" args="/carla/ego_vehicle/lidar/sensor/point_cloud /points_raw"/>

<!-- remap carla front camera to autoware -->
<node pkg="topic_tools" type="relay" name="imag_relay" args="/carla/ego_vehicle/camera/rgb/front/image_color /image_raw"/>

<!-- extract pose from carla odometry -->
<node pkg="carla_autoware_bridge" type="odometry_to_posestamped" name="odometry_to_posestamped"/>

<!-- convert twist to carla ackermann drive-->
<node pkg="carla_autoware_bridge" type="vehiclecmd_to_ackermanndrive" name="vehiclecmd_to_ackermanndrive" output="screen">
<param name="wheelbase" value="$(arg wheelbase)"/>
</node>

<!-- mission planning -->
<include file="$(find carla_autoware_waypoint_publisher)/launch/carla_autoware_waypoint_publisher.launch" />

</launch>

Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
<launch>

<param name="/carla/client/start_in_autopilot" value="False" />

<!-- carla client -->
<include file="$(find carla_client)/launch/carla_manual_client.launch" />

<!-- common -->
<include file="$(find carla_autoware_bridge)/launch/carla_autoware_bridge_common.launch" />

</launch>

Original file line number Diff line number Diff line change
@@ -1,11 +1,24 @@
#!/usr/bin/env python

# Copyright (c) 2019 Intel Labs.
#
# authors: Frederik Pasch
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
#
# This ROS node reads a Twist message from Autoware, converts it to an AckermannDrive message and sends it Carla
#
# If data is sent out can be controlled by topic /actuator_data_forwarding_active

import rospy, math
from ackermann_msgs.msg import AckermannDrive
from autoware_msgs.msg import VehicleCmd
from std_msgs.msg import Bool

pub = rospy.Publisher("/carla/ego_vehicle/ackermann_cmd", AckermannDrive, queue_size=1)
wheelbase = 3.0
actuator_data_forwarding_active = True

def convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase):
if omega == 0 or v == 0:
Expand All @@ -15,15 +28,24 @@ def convert_trans_rot_vel_to_steering_angle(v, omega, wheelbase):

def callback(data):
global wheelbase
global actuator_data_forwarding_active
if not actuator_data_forwarding_active:
return
msg = AckermannDrive()
msg.speed = data.twist_cmd.twist.linear.x
msg.steering_angle = convert_trans_rot_vel_to_steering_angle(msg.speed, data.twist_cmd.twist.angular.z, wheelbase)
pub.publish(msg)

def disableCallback(data):
global actuator_data_forwarding_active
actuator_data_forwarding_active = data.data
rospy.loginfo("Forward actuator data set to %d", actuator_data_forwarding_active)

def twist_to_ackermanndrive():
rospy.init_node('twist_to_ackermanndrive')
wheelbase = rospy.get_param('~wheelbase', 3.0)
rospy.Subscriber("/vehicle_cmd", VehicleCmd, callback, queue_size=1)
rospy.Subscriber("/actuator_data_forwarding_active", Bool, disableCallback, queue_size=1)
rospy.spin()

if __name__ == '__main__':
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,7 @@
#
# Copyright (c) 2019 Intel Labs.
#
# authors: Frederik Pasch (frederik.pasch@intel.com)
# authors: Frederik Pasch
#
import rospy
import carla
Expand Down
3 changes: 1 addition & 2 deletions catkin_ws/src/carla_client/launch/carla_client.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,8 @@
<param name="/carla/host" value="127.0.0.1" />
<param name="/carla/port" value="2000" />
<param name="/carla/client/vehicle_filter" value="vehicle.toyota.prius*" />
<param name="/carla/client/vehicle_filter" value="vehicle.toyota.prius*" />

<!-- set fixed spawn_point (caution: once set, they keep existing between roslaunch executions)
<!-- set fixed spawn_point (caution: once set, the parameters keep existing between roslaunch executions)
<group ns="/carla/client/spawn_point">
<param name="X" value="0.0" />
<param name="Y" value="0.0" />
Expand Down
14 changes: 14 additions & 0 deletions catkin_ws/src/carla_client/launch/carla_manual_client.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
<launch>
<param name="/carla/host" value="127.0.0.1" />
<param name="/carla/port" value="2000" />
<param name="/carla/client/vehicle_filter" value="vehicle.toyota.prius*" />

<group ns="/carla/client/resolution">
<param name="width" value="800" />
<param name="height" value="600" />
</group>

<node pkg="carla_client" type="carla_autoware_manual_control" name="carla_autoware_manual_control" output="screen"/>

</launch>

Empty file.
53 changes: 6 additions & 47 deletions catkin_ws/src/carla_client/src/carla_autoware_control
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
# Barcelona (UAB).
# Copyright (c) 2019 Intel Labs.
#
# authors: Frederik Pasch (frederik.pasch@intel.com)
# authors: Frederik Pasch
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
Expand All @@ -17,6 +17,8 @@ import glob
import os
import random

import carla_autoware_sensors

# ==============================================================================
# -- find carla module ---------------------------------------------------------
# ==============================================================================
Expand Down Expand Up @@ -77,9 +79,9 @@ class World(object):
spawn_point = random.choice(spawn_points) if spawn_points else carla.Transform()
self.player = self.world.try_spawn_actor(blueprint, spawn_point)
# Set up the sensors.
self.gnss_sensor = GnssSensor(self.player)
self.lidar_sensor = LidarSensor(self.player)
self.front_camera = FrontCamera(self.player)
self.gnss_sensor = carla_autoware_sensors.GnssSensor(self.player)
self.lidar_sensor = carla_autoware_sensors.LidarSensor(self.player)
self.front_camera = carla_autoware_sensors.FrontCamera(self.player)
self.view_camera = ViewCamera(self.player)

def destroy(self):
Expand All @@ -94,47 +96,6 @@ class World(object):
if actor is not None:
actor.destroy()

# ==============================================================================
# -- GnssSensor ----------------------------------------------------------------
# ==============================================================================

class GnssSensor(object):
def __init__(self, parent_actor):
self.sensor = None
self._parent = parent_actor
self.lat = 0.0
self.lon = 0.0
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.other.gnss')
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=1.0, z=2.8)), attach_to=self._parent)

# ==============================================================================
# -- LidarSensor ---------------------------------------------------------------
# ==============================================================================

class LidarSensor(object):
def __init__(self, parent_actor):
self.sensor = None
self._parent = parent_actor
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.lidar.ray_cast')
bp.set_attribute('range', '5000')
bp.set_attribute('role_name', 'sensor')
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=0.0, z=2.0)), attach_to=self._parent)

# ==============================================================================
# -- FrontCameraSensor ---------------------------------------------------------
# ==============================================================================

class FrontCamera(object):
def __init__(self, parent_actor):
self.sensor = None
self._parent = parent_actor
world = self._parent.get_world()
bp = world.get_blueprint_library().find('sensor.camera.rgb')
bp.set_attribute('role_name', 'front')
self.sensor = world.spawn_actor(bp, carla.Transform(carla.Location(x=2.0, z=2.0)), attach_to=self._parent)

# ==============================================================================
# -- CameraSensor for Visualization --------------------------------------------
# ==============================================================================
Expand Down Expand Up @@ -182,8 +143,6 @@ def main():
finally:

if world is not None:
rospy.loginfo('DELETING WORLD')

world.destroy()


Expand Down
Loading

0 comments on commit e0f870d

Please sign in to comment.