Skip to content

Commit

Permalink
Add multiple nodes
Browse files Browse the repository at this point in the history
- carla_ros_scenario_runner is a ros node, that is able to control the CARLA scenario runner.
  - scenarios can be executed via ros-service
- carla_ad_agent is a ros node, that provides basic ad functionality
  - derived from carla planning
  - respects traffic lights
  - avoids crashs with other vehicles
- rviz_carla_plugin is a rviz plugin with the following features:
  - provide a pose of the current view (used in carla_spectator_camera)
  - visualize the current vehicle control
  - allows manually overriding the vehicle control
  - execute a scenario
  - pause the simulation (if started in synchronous mode)
- carla_ad_demo provides a demo setup (also including all of the above nodes)
- modify carla_waypoint_publisher service to be able to provide waypoint for an actor id
  • Loading branch information
fred-labs authored and fabianoboril committed Mar 3, 2020
1 parent cb00099 commit d968bc9
Show file tree
Hide file tree
Showing 60 changed files with 3,526 additions and 52 deletions.
4 changes: 4 additions & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
Expand Up @@ -7,6 +7,10 @@
* Add node to convert a twist to a vehicle control command
* Add node carla_spectator_camera
* Update carla_waypoint_publisher
* Add carla_ros_scenario_runner
* Add rviz_carla_plugin
* Add carla_ad_agent
* Add carla_ad_demo

## CARLA-ROS-Bridge 0.9.6

Expand Down
38 changes: 17 additions & 21 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -48,24 +48,18 @@ For more information about configuring a ROS environment see

First run the simulator (see carla documentation: <http://carla.readthedocs.io/en/latest/>)

./CarlaUE4.sh -windowed -ResX=320 -ResY=240
# run carla in background
SDL_VIDEODRIVER=offscreen ./CarlaUE4.sh -opengl

Wait for the message:
Wait a few seconds, then start the ros bridge (choose one option):

Waiting for the client to connect...

Then start the ros bridge (choose one option):

export PYTHONPATH=$PYTHONPATH:<path/to/carla/>/PythonAPI/<your_egg_file>
export PYTHONPATH=$PYTHONPATH:<path-to-carla>/PythonAPI/carla/dist/carla-<carla_version_and_arch>.egg
source ~/carla-ros-bridge/catkin_ws/devel/setup.bash

# Option 1: start the ros bridge
roslaunch carla_ros_bridge carla_ros_bridge.launch

# Option 2: start the ros bridge together with RVIZ
roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch

# Option 3: start the ros bridge together with an example ego vehicle
# Option 2: start the ros bridge together with an example ego vehicle
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch

## Settings
Expand Down Expand Up @@ -267,25 +261,27 @@ The following markers are supported in 'map'-frame:
| ---------------------------------- | ------------------------------------------------------------------------------------------------------ | --------------------------- |
| `/carla/debug_marker` (subscriber) | [visualization_msgs.MarkerArray](http://docs.ros.org/api/visualization_msgs/html/msg/MarkerArray.html) | draw markers in CARLA world |

## Carla Ego Vehicle

`carla_ego_vehicle` provides a generic way to spawn an ego vehicle and attach sensors to it. You can find further documentation [here](carla_ego_vehicle/README.md).

## Carla Infrastructure Sensors

`carla_infrastructure` provides a generic way to spawn a set of infrastructure sensors defined in a config file. You can find further documentation [here](carla_infrastructure/README.md).

## Waypoint calculation
## Additional Functionality

To make use of the Carla waypoint calculation a ROS Node is available to get waypoints. You can find further documentation [here](carla_waypoint_publisher/README.md).
| Name | Description |
| --------------------------------- | ------------------------------------------------------------------------------------------------------- |
| [Carla Ego Vehicle](carla_ego_vehicle/README.md) | Provides a generic way to spawn an ego vehicle and attach sensors to it. |
| [Carla Infrastructure](carla_infrastructure/README.md) | Provides a generic way to spawn a set of infrastructure sensors defined in a config file. |
| [Carla Waypoint Publisher](carla_waypoint_publisher/README.md) | Provide routes and access to the Carla waypoint API |
| [Carla ROS Scenario Runner](carla_ros_scenario_runner/README.md) | ROS node that wraps the functionality of the CARLA [scenario runner](https://github.com/carla-simulator/scenario_runner) to execute scenarios. |
| [Carla AD Agent](carla_ad_agent/README.md) | A basic AD agent, that can follow a route and avoid collisions with other vehicles and stop on red traffic lights. |
| [Carla AD Demo](carla_ad_demo/README.md) | A meta package that provides everything to launch a CARLA ROS environment with an AD vehicle. |
| [RVIZ Carla Plugin](rviz_carla_plugin/README.md) | A [RVIZ](http://wiki.ros.org/rviz) plugin to visualize/control CARLA. |
| [RQT Carla Plugin](rqt_carla_plugin/README.md) | A [RQT](http://wiki.ros.org/rqt) plugin to control CARLA. |

## Troubleshooting

### ImportError: No module named carla

You're missing Carla Python. Please execute:

export PYTHONPATH=$PYTHONPATH:<path/to/carla/>/PythonAPI/<your_egg_file>
export PYTHONPATH=$PYTHONPATH:<path/to/carla/>/PythonAPI/carla/dist/<your_egg_file>

Please note that you have to put in the complete path to the egg-file including
the egg-file itself. Please use the one, that is supported by your Python version.
Expand Down
32 changes: 32 additions & 0 deletions carla_ad_agent/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,32 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_ad_agent)

find_package(catkin REQUIRED COMPONENTS
rospy
roslaunch
)

catkin_python_setup()

roslaunch_add_file_check(launch)

catkin_package(
CATKIN_DEPENDS
rospy
)

catkin_install_python(PROGRAMS
src/carla_ad_agent/carla_ad_agent.py
src/carla_ad_agent/basic_agent.py
src/carla_ad_agent/agent.py
src/carla_ad_agent/local_planner.py
src/carla_ad_agent/vehicle_pid_controller.py
src/carla_ad_agent/misc.py
src/carla_ad_agent/__init__.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)

13 changes: 13 additions & 0 deletions carla_ad_agent/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
# CARLA AD Agent

An AD agent that can follow a given route.

It avoids crashs with other vehicles and respects the state of the traffic lights.

For a more comprehensive solution, have a look at [Autoware](https://www.autoware.ai/).

## Publications

| Topic | Type | Description |
| ---------------------------------- | ------------------- | --------------------------- |
| `/carla/<ROLE NAME>/vehicle_control_cmd` | [carla_msgs.CarlaEgoVehicleControl](../carla_msgs/msg/CarlaEgoVehicleControl.msg) | Vehicle control command |
13 changes: 13 additions & 0 deletions carla_ad_agent/launch/carla_ad_agent.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,13 @@
<!-- -->
<launch>
<arg name="role_name" default="ego_vehicle"/>
<arg name="target_speed" default="20"/>
<arg name="avoid_risk" default="True"/>

<node pkg="carla_ad_agent" type="carla_ad_agent.py" name="carla_ad_agent_$(arg role_name)" output="screen">
<param name="target_speed" value="$(arg target_speed)" />
<param name="role_name" value="$(arg role_name)" />
<param name="avoid_risk" value="$(arg avoid_risk)" />
</node>
</launch>

18 changes: 18 additions & 0 deletions carla_ad_agent/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
<?xml version="1.0"?>
<package format="2">
<name>carla_ad_agent</name>
<version>0.0.1</version>
<description>The carla_ad_agent package</description>
<maintainer email="[email protected]">CARLA Simulator Team</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>roslaunch</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>topic_tools</exec_depend>
<exec_depend>carla_waypoint_types</exec_depend>
<exec_depend>carla_msgs</exec_depend>
<export>
</export>
</package>
10 changes: 10 additions & 0 deletions carla_ad_agent/setup.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
from distutils.core import setup
from catkin_pkg.python_setup import generate_distutils_setup

d = generate_distutils_setup(
packages=['carla_ad_agent'],
package_dir={'': 'src'}
)

setup(**d)

Empty file.
Loading

0 comments on commit d968bc9

Please sign in to comment.