Updated to home02, index.md to be changed.

This commit is contained in:
sergi-e 2020-03-02 16:49:56 +01:00 committed by Marc Garcia Puig
parent 825ec97381
commit 5453da321e
3 changed files with 78 additions and 81 deletions

View File

@ -1,4 +1,4 @@
<h1>ROS bridge installation</h1>
# ROS bridge installation
* [__Requirements__](#requirements)
* [__Bridge installation__](#bridge-installation)
@ -12,9 +12,9 @@ The ROS bridge enables two-way communication between ROS and CARLA.
In order to do so, the information from the CARLA server is translated to ROS topics. For example, the information retrieved by sensors is structured to fit ROS structure.
And also vice versa, the messages sent between nodes in ROS get translated to commands to be applied in CARLA. This is commonly used to update the state of a vehicle and apply controllers.
---------------
##Requirements
<h4>ROS melodic</h4>
---
## Requirements
#### ROS melodic
* __ROS Kinetic/Melodic:__ follow the official documentation to [install ROS](http://wiki.ros.org/melodic/Installation/Ubuntu). Some ROS packages could be necessary, depending on the user needs, such as [rviz](https://wiki.ros.org/ainstein_radar_rviz_plugins) to visualize ROS data.
* __CARLA 0.9.7:__ only this and later versions are supported. Follow the [quick start installation](../getting_started/quickstart) or make the build for the corresponding platform.
@ -22,10 +22,10 @@ And also vice versa, the messages sent between nodes in ROS get translated to co
!!! Important
Make sure that both CARLA and ROS work properly before continuing with the installation.
---------------
##Bridge installation
---
## Bridge installation
<h4>a) apt-get ROS bridge</h4>
#### a) apt-get ROS bridge
First add the apt repository:
@ -47,7 +47,7 @@ sudo apt-get update &&
sudo apt-get install carla-ros-bridge
```
<h4>b) Repository download</h4>
#### b) Repository download
In order to use the ROS bridge a catkin workspace is needed. The ROS bridge should be cloned and built in there to be available.
The following fragment creates a new workspace and clones the repository in there.
@ -69,8 +69,8 @@ rosdep install --from-paths src --ignore-src -r
catkin_make
```
---------------
##Run the ROS bridge
---
## Run the ROS bridge
__1) run CARLA:__ the way to do so will depend on the the CARLA installation chosen, so here is a brief summary:
@ -106,7 +106,7 @@ roslaunch carla_ros_bridge carla_ros_bridge_with_rviz.launch
roslaunch carla_ros_bridge carla_ros_bridge_with_example_ego_vehicle.launch
```
<h4>ImportError: no module named CARLA</h4>
#### ImportError: no module named CARLA
The path to CARLA Python is missing. The apt-get installation does this automatically, but it may be missing for other installations. Execute the following command with the complete path to the _.egg_ file (included). Use the one, that is supported by the Python version installed:
@ -120,9 +120,8 @@ To check the installation, import CARLA from Python and wait for a sucess messag
python -c 'import carla;print("Success")'
```
---------------
##Setting CARLA
---
## Setting CARLA
There is some configuration for CARLA available from the ROS bridge. This can be setup by editing the file: [`share/carla_ros_bridge/config/settings.yaml`](https://github.com/carla-simulator/ros-bridge/blob/master/carla_ros_bridge/config/settings.yaml).
@ -140,7 +139,7 @@ The parameters available refer to:
!!! Warning
In synchronous mode, only the ros-bridge is allowed to tick. Other CARLA clients must passively wait.
<h4>Synchronous mode</h4>
#### Synchronous mode
The following topic allows to control the stepping when in synchronous mode:

View File

@ -1,7 +1,7 @@
<h1>CARLA launch</h1>
# CARLA launch
--------------
##carla_ackermann_control.launch
---
## carla_ackermann_control.launch
Creates a node to manage a vehicle using Ackermann controls instead of the CARLA control messages when these are not ideal to connect an AD stack. The node reads the vehicle info from CARLA and uses it to define the controller. A simple Python PID is used to adjust acceleration/velocity. It can be installed using:
```sh
@ -29,8 +29,8 @@ Speed is in __m/s__, steering angle is driving angle (not wheel angle) in __radi
* <font color="80ba10"><b>/carla/ego_vehicle/ackermann_control/parameter_updates</b></font> — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure)
* <font color="80ba10"><b>/carla/ego_vehicle/vehicle_control_cmd</b></font> — [carla_msgs.CarlaEgoVehicleControl](../ros_msgs#carlaegovehiclecontrolmsg)
---------------
##carla_ego_vehicle.launch
---
## carla_ego_vehicle.launch
Spawns an ego vehicle (`role-name="ego_vehicle"`) with the argument `sensor_definition_file` being this the location of a __.json__ file describing sensors attached to the vehicle. The format for this file is explained [here](https://github.com/carla-simulator/ros-bridge/tree/master/carla_ego_vehicle).
To spawn the vehicle at a specific location, publish in: `/carla/ego_vehicle/initialpose` or use __RVIZ__ and select a position with: __2D Pose estimate__.
@ -44,8 +44,8 @@ Spawns an ego vehicle with sensors attached and waits for world information.
* <font color="f8815c"><b>/carla/ego_vehicle/initialpose</b></font> — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)
* <font color="f8815c"><b>/carla/world_info</b></font> — [carla_msgs.CarlaWorldInfo](../ros_msgs#carlaworldinfomsg)
---------------
##carla_example_ego_vehicle.launch
---
## carla_example_ego_vehicle.launch
As [carla_ego_vehicle.launch](#carla-ego-vehicle-launch), spawns an ego vehicle (`role-name="ego_vehicle"`), only this uses a provided file to pass the sensors attached to the vehicle. Said file can be found in: `share/carla_ego_vehicle/config/sensors.json`.
<!---NODE-->
@ -57,8 +57,8 @@ Spawns an ego vehicle with sensors attached and waits for world information.
* <font color="f8815c"><b>/carla/ego_vehicle/initialpose</b></font> — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)
* <font color="f8815c"><b>/carla/world_info</b></font> — [carla_msgs.CarlaWorldInfo](../ros_msgs#carlaworldinfomsg)
---------------
##carla_infrastructure.launch
---
## carla_infrastructure.launch
Spawns infrastructure sensors and requires the argument `infrastructure_sensor_definition_file` with the location of a __.json__ file describing these sensors.
<!---NODE-->
@ -69,9 +69,8 @@ Spawns the infrastructure sensors passed as arguments.
* <font color="f8815c"><b>/carla/world_info</b></font> — [carla_msgs.CarlaWorldInfo](../ros_msgs#carlaworldinfomsg)
---------------
##carla_ros_bridge.launch
---
## carla_ros_bridge.launch
Creates a node with some basic communication between CARLA and ROS.
<!---NODE-->
@ -91,9 +90,8 @@ Receives the debug shapes being drawn, which include: arrows, points, cubes and
* <font color="80ba10"><b>/carla/traffic_lights</b></font> — [carla_msgs.CarlaTrafficLightStatusList](../ros_msgs#carlatrafficlightstatuslist)
* <font color="80ba10"><b>/carla/world_info</b></font> — [carla_msgs.CarlaWorldInfo](../ros_msgs#carlaworldinfomsg)
--------------
##carla_ros_bridge_with_ackermann_control.launch
---
## carla_ros_bridge_with_ackermann_control.launch
Launches two basic nodes, one to retrieve simulation data and another one to control a vehicle using [AckermannDrive messages](http://docs.ros.org/jade/api/ackermann_msgs/html/msg/AckermannDrive.htm).
@ -133,8 +131,8 @@ Speed is in __m/s__, steering angle is driving angle (not wheel angle) in __radi
* <font color="80ba10"><b>/carla/ego_vehicle/ackermann_control/parameter_updates</b></font> — [dynamic_reconfigure/Config](http://wiki.ros.org/dynamic_reconfigure)
* <font color="80ba10"><b>/carla/ego_vehicle/vehicle_control_cmd</b></font> — [carla_msgs.CarlaEgoVehicleControl](../ros_msgs#carlaegovehiclecontrolmsg)
--------------
##carla_ros_bridge_with_example_ego_vehicle.launch
---
## carla_ros_bridge_with_example_ego_vehicle.launch
Spawns an ego vehicle with sensors attached and starts communication between CARLA and ROS sharing current simulation state, sensor and ego vehicle data.
The ego vehicle is set ready to be used in manual control.
@ -204,8 +202,8 @@ Spawns an ego vehicle with sensors attached and waits for world information.
* <font color="f8815c"><b>/carla/ego_vehicle/initialpose</b></font> — [geometry_msgs/PoseWithCovarianceStamped](http://docs.ros.org/melodic/api/geometry_msgs/html/msg/PoseWithCovarianceStamped.html)
---------------
##carla_ros_bridge_with_rviz.launch
---
## carla_ros_bridge_with_rviz.launch
Starts some basic communication between CARLA and ROS and launches an instance of RVIZ ready to retrieve Lidar data.
<!---NODE-->
<h4 style="margin-bottom: 5px"> <u>carla_ros_bridge</u> <small><i>(Node)</i></small> </h4>
@ -234,8 +232,8 @@ Runs an instance of RVIZ waiting for Lidar data.
* <font color="f8815c"><b>/carla/ego_vehicle/lidar/front/point_cloud</b></font> — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html)
--------------
##carla_manual_control.launch
---
## carla_manual_control.launch
A ROS version of the CARLA script `manual_control.py` that receives and manages the information using ROS topics. It has some prerequisites:
@ -268,8 +266,8 @@ The information retrieved includes both static and current state, the sensor dat
* <font color="80ba10"><b>/carla/ego_vehicle/vehicle_control_cmd_manual</b></font> — [carla_msgs.CarlaEgoVehicleControl](../ros_msgs#carlaegovehiclecontrolmsg)
* <font color="80ba10"><b>/carla/ego_vehicle/vehicle_control_manual_override</b></font> — [std_msgs.Bool](http://docs.ros.org/melodic/api/std_msgs/html/msg/Bool.html)
--------------
##carla_pcl_recorder.launch
---
## carla_pcl_recorder.launch
Creates a pointcloud map for the current CARLA level by letting an ego vehicle in autopilot mode roam around with a Lidar sensor attached.
The captured point clouds are saved in the `/tmp/pcl_capture` directory. Once the capture is done, the overall size can be reduced:
```sh
@ -370,8 +368,8 @@ Receives the cloud point data to map the surroundings.
* <font color="80ba10"><b>/carla/ego_vehicle/lidar/lidar1/point_cloud</b></font> — [sensor_msgs.PointCloud2](http://docs.ros.org/melodic/api/sensor_msgs/html/msg/PointCloud2.html)
--------------
##carla_waypoint_publisher.launch
---
## carla_waypoint_publisher.launch
Calculates a waypoint route for an ego vehicle.
The calculated route is published in: `/carla/<ego vehicle name>/waypoints`.

View File

@ -1,4 +1,4 @@
<h1>CARLA messages</h1>
# CARLA messages
The following reference lists all the CARLA messages available in the ROS bridge. These will can be used to enable communication in both ways.
Any doubts regarding these messages or the CARLA-ROS bridge can be solved in the forum:
@ -11,8 +11,8 @@ CARLA forum</a>
</p>
</div>
---------------
##CarlaActorInfo.msg
---
## CarlaActorInfo.msg
Comprises the information regarding an actor to be shared between ROS and CARLA.
The [CarlaActorList.msg](#carlaactorlist) message is a list of these items.
@ -24,8 +24,8 @@ The [CarlaActorList.msg](#carlaactorlist) message is a list of these items.
| `type` | string | The identifier of the blueprint this actor was based on. |
| `rolename` | string | Role assigned to the actor when spawned. |
---------------
##CarlaActorList.msg
---
## CarlaActorList.msg
Contains a list of messages with some basic information for CARLA actors.
@ -33,8 +33,8 @@ Contains a list of messages with some basic information for CARLA actors.
| ----------- | ---------------- | ----------- |
| `actors` | [CarlaActorInfo](#carlaactorinfomsg)[] | List of messages with actors' information. |
---------------
##CarlaCollisionEvent.msg
---
## CarlaCollisionEvent.msg
Registers information regarding a collision event detected by the collision sensor of an actor.
@ -44,8 +44,8 @@ Registers information regarding a collision event detected by the collision sens
| `other_actor_id` | uint32 | ID of the actor against whom the collision was detected. |
| `normal_impulse` | geometry_msgs/Vector3 | Vector representing resulting impulse from the collision. |
---------------
##CarlaControl.msg
---
## CarlaControl.msg
These messages are used to control the simulation while in synchronous mode. The constant defined is translated as stepping commands.
@ -56,8 +56,8 @@ These messages are used to control the simulation while in synchronous mode. The
!!! Important
In synchronous mode, only the ROS bridge client is allowed to tick.
---------------
##CarlaEgoVehicleControl.msg
---
## CarlaEgoVehicleControl.msg
Messages sent to apply a control to a vehicle in both modes, normal and manual. These are published in a stack.
@ -72,8 +72,8 @@ Messages sent to apply a control to a vehicle in both modes, normal and manual.
| `gear` | int32 | Changes between the available gears in a vehicle. |
| `manual_gear_shift` | bool | If ture, the gears will be shifted using `gear`. |
---------------
##CarlaEgoVehicleInfo.msg
---
## CarlaEgoVehicleInfo.msg
Contains some static information regarding a vehicle, mostly the attributes that used to define its physics.
@ -95,8 +95,8 @@ Contains some static information regarding a vehicle, mostly the attributes that
| `drag_coefficient` | float32 | Drag coefficient of the vehicle's chassis. |
| `center_of_mass` | geometry_msgs/Vector3 | The center of mass of the vehicle. |
---------------
##CarlaEgoVehicleInfoWheel.msg
---
## CarlaEgoVehicleInfoWheel.msg
Contains some static information regarding a wheel that will be part of a [CarlaEgoVehicleInfo.msg](#carlaegovehicleinfo) message.
@ -110,8 +110,8 @@ Contains some static information regarding a wheel that will be part of a [Carla
| `max_handbrake_torque` | float32 | The maximum handbrake torque in Nm. |
| `position` | gemoetry_msgs/Vector3 | World position of the wheel. |
---------------
##CarlaEgoVehicleStatus.msg
---
## CarlaEgoVehicleStatus.msg
Details the current status of the vehicle as an object in the world.
@ -123,8 +123,8 @@ Details the current status of the vehicle as an object in the world.
| `orientation` | geometry_msgs/Quaternion | Current orientation of the vehicle. |
| `control` | [CarlaEgoVehicleControl](#carlaegovehiclecontrol) | Current control values as reported by CARLA. |
---------------
##CarlaLaneInvasionEvent.msg
---
## CarlaLaneInvasionEvent.msg
These messages are used to publish lane invasions detected by a lane-invasion sensor attached to a vehicle. The invasions detected in the last step are passed as a list with a constant definition to identify the lane crossed.
@ -133,8 +133,8 @@ These messages are used to publish lane invasions detected by a lane-invasion se
| `header` | [Header](http://docs.ros.org/melodic/api/std_msgs/html/msg/Header.html) | Time stamp and frame ID when the message is published. |
| `crossed_lane_markings` | int32[] | __LANE_MARKING_OTHER__=0 <br> __LANE_MARKING_BROKEN__=1 <br> __LANE_MARKING_SOLID__=2 |
---------------
##CarlaStatus.msg
---
## CarlaStatus.msg
Details the current world settings of hte simulation.
@ -145,8 +145,8 @@ Details the current world settings of hte simulation.
| `synchronous_mode` | bool | If true, synchronous mode is enabled. |
| `synchronous_mode_running` | bool | True when the simulation is running. False when it is paused. |
---------------
##CarlaTrafficLightStatus.msg
---
## CarlaTrafficLightStatus.msg
Contains a constant definition regarding the state of a traffic light.
@ -155,8 +155,8 @@ Contains a constant definition regarding the state of a traffic light.
| `id` | uint32 | ID of the traffic light actor. |
| `state` | uint8 | __RED__=0,__YELLOW__=1, __GREEN__=2, __OFF__=3, __UNKNOWN__=4 |
---------------
##CarlaTrafficLightStatusList.msg
---
## CarlaTrafficLightStatusList.msg
Comprises a list of all traffic lights with their status.
@ -164,8 +164,8 @@ Comprises a list of all traffic lights with their status.
| ---------------- | ----------------------------------------------------- | ---------------- |
| `traffic_lights` | [CarlaTrafficLightStatus](#carlatrafficlightstatus)[] | A list of messages summarizing traffic light states. |
---------------
##CarlaWalkerControl.msg
---
## CarlaWalkerControl.msg
Contains the information needed to apply a movement controller to a walker.
@ -175,8 +175,8 @@ Contains the information needed to apply a movement controller to a walker.
| `speed` | float32 | A scalar value to control the walker's speed. |
| `jump` | bool | If true, the walker will jump. |
---------------
##CarlaWaypoint.msg
---
## CarlaWaypoint.msg
Summarizes data regarding a waypoint.
@ -188,8 +188,8 @@ Summarizes data regarding a waypoint.
| `is_junction` | bool | __True__ if the current Waypoint is on a junction as defined by OpenDRIVE. |
| `pose` | [geometry_msgs/Pose](http://docs.ros.org/api/geometry_msgs/html/msg/Pose.html) | Position and orientation of the waypoint. |
---------------
##CarlaWorldInfo.msg
---
## CarlaWorldInfo.msg
Information about the current CARLA map (name and OpenDRIVE).
@ -198,8 +198,8 @@ Information about the current CARLA map (name and OpenDRIVE).
| `map_name` | string | Name of the CARLA map loaded in the current world. |
| `opendrive` | string | .xodr OpenDRIVE file of the current map as a string. |
---------------
##EgoVehicleControlCurrent.msg
---
## EgoVehicleControlCurrent.msg
Represents the current time and the speed and acceleration values of the vehicle used by the controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message.
@ -210,8 +210,8 @@ Represents the current time and the speed and acceleration values of the vehicle
| `speed_abs` | float32 | Speed as an absolute value. |
| `accel` | float32 | Current acceleration applied by the controller. |
---------------
##EgoVehicleControlInfo.msg
---
## EgoVehicleControlInfo.msg
Contains all the current values used within an Ackermann controller. These messages are useful for debugging.
@ -225,8 +225,8 @@ Contains all the current values used within an Ackermann controller. These messa
| `output` | [CarlaEgoVehicleControl](#carlaegovehiclecontrolmsg) | Output controller that will be applied in CARLA. |
---------------
##EgoVehicleControlMaxima.msg
---
## EgoVehicleControlMaxima.msg
Represents the maximum values that restrict the controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message.
@ -239,8 +239,8 @@ Represents the maximum values that restrict the controller. It is part of a `Car
| `min_accel` | float32 | Min. acceleration for a vehicle. When the Ackermann taget accel. exceeds this value, the input accel. is controlled. |
| `max_pedal` | float32 | ??? |<!---- what?>
---------------
##EgoVehicleControlStatus.msg
---
## EgoVehicleControlStatus.msg
Represents the current status of the ego vehicle controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message.
@ -255,8 +255,8 @@ Represents the current status of the ego vehicle controller. It is part of a `Ca
| `brake_upper_border` | float32 | ??? Borders for lay off pedal. |<!---- what?>
| `throttle_lower_border` | float32 | ??? Borders for lay off pedal. |<!---- what?>
---------------
##EgoVehicleControlTarget.msg
---
## EgoVehicleControlTarget.msg
Represents the target vallues for the variables of the ego vehicle controller. It is part of a `Carla_Ackermann_Control.EgoVehicleControlInfo.msg` message.