Skip to content

Commit

Permalink
Added the initial files for ROS documentation as a sub project of CARLA
Browse files Browse the repository at this point in the history
  • Loading branch information
corkyw10 committed Mar 5, 2021
1 parent fc36cda commit 864544f
Show file tree
Hide file tree
Showing 20 changed files with 1,718 additions and 0 deletions.
14 changes: 14 additions & 0 deletions .readthedocs.yml
@@ -0,0 +1,14 @@
# Read the Docs configuration file
# See https://docs.readthedocs.io/en/stable/config-file/v2.html for details

version: 2

mkdocs:
configuration: mkdocs.yml

formats: all

python:
version: 3.7
install:
- requirements: docs/requirements.txt
69 changes: 69 additions & 0 deletions docs/carla_ackermann_control.md
@@ -0,0 +1,69 @@
# Carla Ackermann Control

The `carla_ackermann_control` package is used to control a CARLA vehicle with [Ackermann messages][ackermanncontrolmsg]. The package converts the Ackermann messages into [CarlaEgoVehicleControl][carlaegovehiclecontrolmsg] messages. It reads vehicle information from CARLA and passes that information to a Python based PID controller called `simple-pid` to control the acceleration and velocity.

[ackermanncontrolmsg]: https://docs.ros.org/en/api/ackermann_msgs/html/msg/AckermannDrive.html
[carlaegovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#carlaegovehiclecontrolmsg

- [__Install the PID controller library__](#install-the-pid-controller-library)
- [__Configuration__](#configuration)
- [__Available Topics__](#available-topics)
- [__Testing control messages__](#testing-control-messages)
---

### Install the PID controller library

Install the PID controller:
```
python3 -m pip install simple-pid
```

---

### Configuration

Parameters can be set both initially in a [configuration file][ackermanconfig] and during runtime via ROS [dynamic reconfigure][rosdynamicreconfig].

[ackermanconfig]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_ackermann_control/config/settings.yaml
[rosdynamicreconfig]: https://wiki.ros.org/dynamic_reconfigure

---

### Available topics

|Topic|Type|Description|
|--|--|--|
|`/carla/<ROLE NAME>/ackermann_cmd` | [ackermann_msgs.AckermannDrive][ackermanncontrolmsg] | __Subscriber__ for steering commands |
| `/carla/<ROLE NAME>/ackermann_control/control_info` | [carla_ackermann_control.EgoVehicleControlInfo][egovehiclecontrolmsg] | The current values used within the controller (useful for debugging) |

[egovehiclecontrolmsg]: https://carla.readthedocs.io/en/latest/ros_msgs/#egovehiclecontrolinfomsg

<br>

---

### Testing control messages

Test the setup by sending commands to the car via the topic `/carla/<ROLE NAME>/ackermann_cmd`. For example, move an ego vehicle with the role name of `ego_vehicle` forward at a speed of 10 meters/sec by running this command:

```bash

# ROS 1
rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10

# ROS 2
ros2 topic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10

```

Or make the vehicle move forward while turning at an angle of 1.22 radians:

```bash

# ROS 1
rostopic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10

# ROS 2
ros2 topic pub /carla/ego_vehicle/ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 1.22, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0, jerk: 0.0}" -r 10

```
67 changes: 67 additions & 0 deletions docs/carla_manual_control.md
@@ -0,0 +1,67 @@
# Carla Manual Control

This package is a ROS only version of the [`manual_control.py`][manualcontrol] script that comes packaged with CARLA. All data is received via ROS topics.

[manualcontrol]: https://github.com/carla-simulator/carla/blob/master/PythonAPI/examples/manual_control.py

- [__Requirements__](#requirements)
- [__Run the package__](#run-the-package)
---

## Requirements

To be able to use `carla_manual_control`, some specific sensors need to be attached to the ego vehicle (see [Carla Spawn Objects](carla_spawn_objects.md) for information on how to attach sensors to vehicles):

- __to display an image__: a camera with role-name 'view' and resolution 800x600
- __to display the current GNSS position__: a GNSS sensor with role-name 'gnss1'
- __to get a notification on lane invasions__: a lane invasion sensor
- __to get a notification on collisons__: a collision sensor

---

## Run the package

To run the package:

__ 1.__ Make sure you have CARLA runing. Start the ROS bridge:

```sh
# ROS 1
roslaunch carla_ros_bridge carla_ros_bridge.launch

# ROS 2
ros2 launch carla_ros_bridge carla_ros_bridge.launch.py
```

__2.__ Spawn objects:

```sh
# ROS 1
roslaunch carla_spawn_objects carla_spawn_objects.launch

# ROS 2
ros2 launch carla_spawn_objects carla_spawn_objects.launch.py
```

__3.__ Launch the `carla_manual_control` node:

```sh
# ROS 1
roslaunch carla_manual_control carla_manual_control.launch

# ROS 2
ros2 launch carla_manual_control carla_manual_control.launch.py
```

__4.__ To steer the vehicle manually, press 'B'. Press 'H' to see instructions.

All of the above commands are also combined into one single launchfile and can be run at the same time by executing the following:

```sh
# ROS 1
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch

# ROS 2
ros2 launch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch.py
```
---
142 changes: 142 additions & 0 deletions docs/carla_spawn_objects.md
@@ -0,0 +1,142 @@
# Carla Spawn Objects

The `carla_spawn_objects` package is used to spawn actors (vehicles, sensors, walkers) and to attach sensors to them.

- [__Configuration and sensor setup__](#configuration-and-sensor-setup)
- [Create the configuration](#create-the-configuration)
- [__Spawning Vehicles__](#spawning-vehicles)
- [Respawning vehicles](#respawning-vehicles)
- [__Spawning Sensors__](#spawning-sensors)
- [Attach sensors to an existing vehicle](#attach-sensors-to-an-existing-vehicle)

---

## Configuration and sensor setup

Objects and their attached sensors are defined through a `.json` file. The default location of this file is within `carla_spawn_objects/config/objects.json`. To change the location, pass the path to the file via the private ROS parameter, `objects_definition_file`, when you launch the package:

```sh
# ROS 1
roslaunch carla_spawn_objects carla_spawn_objects.launch objects_definition_file:=path/to/objects.json

# ROS 2
ros2 launch carla_spawn_objects carla_spawn_objects.launch.py objects_definition_file:=path/to/objects.json
```


### Create the configuration

You can find an example in the [ros-bridge repository][objectsjson] as well as follow this outline to create your own configuration and sensor setup:

```json
{
"objects":
[
{
"type": "<SENSOR-TYPE>",
"id": "<NAME>",
"spawn_point": {"x": 0.0, "y": 0.0, "z": 0.0, "roll": 0.0, "pitch": 0.0, "yaw": 0.0},
<ADDITIONAL-SENSOR-ATTRIBUTES>
},
{
"type": "<VEHICLE-TYPE>",
"id": "<VEHICLE-NAME>",
"spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7},
"sensors":
[
<SENSORS-TO-ATTACH-TO-VEHICLE>
]
}
...
]
}
```


!!! Note
Remember when directly defining positions that ROS uses a [right hand system](https://www.ros.org/reps/rep-0103.html#chirality)

All sensor attributes are defined as described in the [blueprint library](https://carla.readthedocs.io/en/latest/bp_library/).

[objectsjson]: https://github.com/carla-simulator/ros-bridge/blob/master/carla_spawn_objects/config/objects.json

---

## Spawning vehicles

- If no specific spawn point is defined, vehicles will be spawned at a random location.
- To define the position at which a vehicle will be spawned, there are two choices:

- Pass the desired position to a ROS parameter `spawn_point_<VEHICLE-NAME>`. `<VEHICLE-NAME>` will be the `id` you gave the vehicle in the `.json` file:

# ROS 1
roslaunch carla_spawn_objects carla_spawn_objects.launch spawn_point_<VEHICLE-NAME>:=x,y,z,roll,pitch,yaw

# ROS 2
ros2 launch carla_spawn_objects carla_spawn_objects.launch.py spawn_point_<VEHICLE-NAME>:=x,y,z,roll,pitch,yaw

- Define the initial position directly in the `.json` file:

{
"type": "vehicle.*",
"id": "ego_vehicle",
"spawn_point": {"x": -11.1, "y": 138.5, "z": 0.2, "roll": 0.0, "pitch": 0.0, "yaw": -178.7},
}

### Respawning vehicles

A vehicle can be respawned to a different location during a simulation by publishing to the topic `/carla/<ROLE NAME>/<CONTROLLER_ID>/initialpose`. To use this functionality:

1. Attach an `actor.pseudo.control` pseudo-actor to the vehicle in the `.json` file. It should have the same `id` value as the value passed as `<CONTROLLER_ID>` used to publish to the topic:

{
"type": "vehicle.*",
"id": "ego_vehicle",
"sensors":
[
{
"type": "actor.pseudo.control",
"id": "control"
}
]
}

2. Launch the `set_inital_pose` node, passing the `<CONTROLLER_ID>` as an argument to the ROS parameter `controller_id` (default = 'control'):

roslaunch carla_spawn_objects set_initial_pose.launch controller_id:=<CONTROLLER_ID>

3. The preferred way to publish the message to set the new position is by using the __2D Pose Estimate__ button available in the RVIZ interface. You can then click on the viewport of the map to respawn in that position. This will delete the current `ego_vehicle` and respawn it at the specified position.

> ![rviz_set_start_goal](images/rviz_set_start_goal.png)
---

## Spawning Sensors

- The initial position for a sensor should be defined directly in the `.json` file, as shown above for vehicles.
- The spawn point for a sensor attached to a vehicle is considered relative to the vehicle.

### Attach sensors to an existing vehicle

Sensors can be attached to an already existing vehicle. To do so:

1. Define the pseudo sensor `sensor.pseudo.actor_list` in the `.json` file. This will give access to a list of already existing actors.

...
{
"type": "sensor.pseudo.actor_list",
"id": "actor_list"
},

2. Define the rest of the sensors as required.
3. Launch the node with the `spawn_sensors_only` parameter set to True. This will check if an actor with the same `id` and `type` as the one specified in the `.json` file is already active and if so, attach the sensors to this actor.

# ROS 1
roslaunch carla_spawn_objects carla_spawn_objects.launch spawn_sensors_only:=True

# ROS 2
ros2 launch carla_spawn_objects carla_spawn_objects.launch.py spawn_sensors_only:=True


---

0 comments on commit 864544f

Please sign in to comment.