Skip to content

Commit

Permalink
Merge pull request #91 from carla-simulator/feature/further_cleanup
Browse files Browse the repository at this point in the history
Feature/further cleanup
  • Loading branch information
fabianoboril committed Apr 5, 2019
2 parents b88815a + 814af5c commit 71e6ffa
Show file tree
Hide file tree
Showing 34 changed files with 185 additions and 96 deletions.
1 change: 1 addition & 0 deletions CHANGELOG.md
Original file line number Diff line number Diff line change
@@ -1,5 +1,6 @@
## Latest changed

* rename gnss topic from '../gnss' to '../fix'
* Add lane invasion sensor
* Add collision sensor
* Rename CarlaVehicleControl to CarlaEgoVehicleControl (and add some more message types)
Expand Down
12 changes: 6 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ This documentation is for CARLA versions *newer* than 0.9.4.

#install required ros-dependencies
rosdep update
rosdep install --from-path .
rosdep install --from-paths src --ignore-src -r

#build
catkin_make
Expand Down Expand Up @@ -124,21 +124,21 @@ Currently the following sensors are supported:

|Topic | Type |
|-------------------------------|------|
| `/carla/<ROLE NAME>/collision` | [carla_ros_bridge.CarlaCollisionEvent](carla_ros_bridge/msg/CarlaCollisionEvent.msg) |
| `/carla/<ROLE NAME>/collision` | [carla_ros_bridge_msgs.CarlaCollisionEvent](carla_ros_bridge_msgs/msg/CarlaCollisionEvent.msg) |

#### Lane Invasion Sensor

|Topic | Type |
|-------------------------------|------|
| `/carla/<ROLE NAME>/lane_invasion` | [carla_ros_bridge.CarlaLaneInvasionEvent](carla_ros_bridge/msg/CarlaLaneInvasionEvent.msg) |
| `/carla/<ROLE NAME>/lane_invasion` | [carla_ros_bridge_msgs.CarlaLaneInvasionEvent](carla_ros_bridge_msgs/msg/CarlaLaneInvasionEvent.msg) |

### Control

|Topic | Type |
|--------------------------------------|------|
| `/carla/<ROLE NAME>/vehicle_control_cmd` (subscriber) | [carla_ros_bridge.CarlaEgoVehicleControl](carla_ros_bridge/msg/CarlaEgoVehicleControl.msg) |
| `/carla/<ROLE NAME>/vehicle_status` | [carla_ros_bridge.CarlaEgoVehicleStatus](carla_ros_bridge/msg/CarlaEgoVehicleStatus.msg) |
| `/carla/<ROLE NAME>/vehicle_info` | [carla_ros_bridge.CarlaEgoVehicleInfo](carla_ros_bridge/msg/CarlaEgoVehicleInfo.msg) |
| `/carla/<ROLE NAME>/vehicle_control_cmd` (subscriber) | [carla_ros_bridge_msgs.CarlaEgoVehicleControl](carla_ros_bridge_msgs/msg/CarlaEgoVehicleControl.msg) |
| `/carla/<ROLE NAME>/vehicle_status` | [carla_ros_bridge_msgs.CarlaEgoVehicleStatus](carla_ros_bridge_msgs/msg/CarlaEgoVehicleStatus.msg) |
| `/carla/<ROLE NAME>/vehicle_info` | [carla_ros_bridge_msgs.CarlaEgoVehicleInfo](carla_ros_bridge_msgs/msg/CarlaEgoVehicleInfo.msg) |

You can stear the ego vehicle from the commandline by publishing to the topic `/carla/<ROLE NAME>/vehicle_control_cmd`.

Expand Down
6 changes: 2 additions & 4 deletions carla_ackermann_control/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,10 +6,9 @@ find_package(catkin REQUIRED COMPONENTS
message_generation
rospy
std_msgs
geometry_msgs
ackermann_msgs
dynamic_reconfigure
carla_ros_bridge
carla_ros_bridge_msgs
)

catkin_python_setup()
Expand All @@ -26,8 +25,7 @@ add_message_files(
generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
carla_ros_bridge
carla_ros_bridge_msgs
)

generate_dynamic_reconfigure_options(
Expand Down
2 changes: 1 addition & 1 deletion carla_ackermann_control/msg/EgoVehicleControlInfo.msg
Original file line number Diff line number Diff line change
Expand Up @@ -21,4 +21,4 @@ EgoVehicleControlCurrent current
EgoVehicleControlStatus status

# the current control output to CARLA
carla_ros_bridge/CarlaEgoVehicleControl output
carla_ros_bridge_msgs/CarlaEgoVehicleControl output
3 changes: 2 additions & 1 deletion carla_ackermann_control/package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -7,13 +7,14 @@
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_depend>carla_ros_bridge_msgs</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>ackermann_msgs</exec_depend>
<exec_depend>carla_ros_bridge</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
<exec_depend>dynamic_reconfigure</exec_depend>
<exec_depend>carla_ros_bridge_msgs</exec_depend>
<export>
</export>
</package>
Original file line number Diff line number Diff line change
Expand Up @@ -18,9 +18,9 @@

from dynamic_reconfigure.server import Server
from ackermann_msgs.msg import AckermannDrive
from carla_ros_bridge.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error
from carla_ros_bridge.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module,import-error
from carla_ros_bridge.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module,import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module,import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module,import-error
from carla_ackermann_control.msg import EgoVehicleControlInfo # pylint: disable=no-name-in-module,import-error
from carla_ackermann_control.cfg import EgoVehicleControlParameterConfig # pylint: disable=no-name-in-module,import-error
import carla_control_physics as phys # pylint: disable=relative-import
Expand Down
1 change: 0 additions & 1 deletion carla_ego_vehicle/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,6 @@ catkin_package(
catkin_install_python(PROGRAMS
src/carla_ego_vehicle/carla_example_ego_vehicle.py
src/carla_ego_vehicle/carla_ego_vehicle_base.py
src/carla_ego_vehicle/carla_ros_manual_control.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

Expand Down
28 changes: 1 addition & 27 deletions carla_ego_vehicle/README.md
Original file line number Diff line number Diff line change
@@ -1,13 +1,5 @@
# ROS Ego Vehicle

This package provides two ROS nodes:

- Carla Example Ego Vehicle: A reference client for spawning an ego vehicle
- Carla ROS Manual Control: a ROS-only manual control


## Carla Example Ego Vehicle

The reference Carla client `carla_example_ego_vehicle` can be used to spawn an ego vehicle (role-name: "ego_vehicle") with the following sensors attached to it.

- GNSS
Expand All @@ -16,7 +8,7 @@ The reference Carla client `carla_example_ego_vehicle` can be used to spawn an e
- Collision Sensor
- Lane Invasion Sensor

Info: To be able to use carla_ros_manual_control a camera with role-name 'view' is required.
Info: To be able to use `carla_manual_control` a camera with role-name 'view' and resolution of 800x600 is required.

If no specific position is set, the ego vehicle is spawned at a random position.

Expand Down Expand Up @@ -47,21 +39,3 @@ The format is a list of dictionaries. One dictionary has the values as follows:
<ADDITIONAL-SENSOR-ATTRIBUTES>
}

## Carla ROS Manual Control

The node `carla_ros_manual_control` is a ROS-only version of the Carla `manual_control.py`. All data is received
via ROS topics.

Note: To be able to use carla_ros_manual_control a camera with role-name 'view' needs to be spawned by `carla_ego_vehicle`.


### Manual steering

In order to steer manually, you might need to disable sending vehicle control commands within another ROS node.

Therefore the manual control is able to publish to `/vehicle_control_manual_override` ([std_msgs/Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html)).

Press `B` to toggle the value.

Note: As sending the vehicle control commands is highly dependent on your setup, you need to implement the subscriber to that topic yourself.

7 changes: 0 additions & 7 deletions carla_ego_vehicle/launch/carla_ros_manual_control.launch

This file was deleted.

Original file line number Diff line number Diff line change
Expand Up @@ -151,12 +151,12 @@ def setup_sensors(self, sensors):
roll=sensor_spec['roll'],
yaw=sensor_spec['yaw'])
elif sensor_spec['type'].startswith('sensor.lidar'):
bp.set_attribute('range', '200')
bp.set_attribute('rotation_frequency', '10')
bp.set_attribute('channels', '32')
bp.set_attribute('upper_fov', '15')
bp.set_attribute('lower_fov', '-30')
bp.set_attribute('points_per_second', '500000')
bp.set_attribute('range', str(sensor_spec['range']))
bp.set_attribute('rotation_frequency', str(sensor_spec['rotation_frequency']))
bp.set_attribute('channels', str(sensor_spec['channels']))
bp.set_attribute('upper_fov', str(sensor_spec['upper_fov']))
bp.set_attribute('lower_fov', str(sensor_spec['lower_fov']))
bp.set_attribute('points_per_second', str(sensor_spec['points_per_second']))
sensor_location = carla.Location(x=sensor_spec['x'], y=sensor_spec['y'],
z=sensor_spec['z'])
sensor_rotation = carla.Rotation(pitch=sensor_spec['pitch'],
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ def sensors(self):
},
{
'type': 'sensor.lidar.ray_cast',
'role_name': 'front',
'role_name': 'lidar1',
'x': 0.0, 'y': 0.0, 'z': 2.4, 'roll': 0.0, 'pitch': 0.0, 'yaw': 0.0,
'range': 5000,
'channels': 32,
Expand All @@ -51,17 +51,17 @@ def sensors(self):
},
{
'type': 'sensor.other.gnss',
'role_name': 'sensor',
'role_name': 'gnss1',
'x': 1.0, 'y': 0.0, 'z': 2.0
},
{
'type': 'sensor.other.collision',
'role_name': 'sensor',
'role_name': 'collision1',
'x': 0.0, 'y': 0.0, 'z': 0.0
},
{
'type': 'sensor.other.lane_invasion',
'role_name': 'sensor',
'role_name': 'laneinvasion1',
'x': 0.0, 'y': 0.0, 'z': 0.0
}
]
Expand Down
22 changes: 22 additions & 0 deletions carla_manual_control/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -0,0 +1,22 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_manual_control)

find_package(catkin REQUIRED COMPONENTS
rospy
)

catkin_python_setup()

catkin_package(
CATKIN_DEPENDS
rospy
)

catkin_install_python(PROGRAMS
src/carla_manual_control/carla_manual_control.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
)
23 changes: 23 additions & 0 deletions carla_manual_control/README.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,23 @@
# Carla Manual Control

The node `carla_manual_control` is a ROS-only version of the Carla `manual_control.py`. All data is received
via ROS topics.

## Prerequistes
To be able to use `carla_manual_control`, some sensors need to be attached to the ego vehicle:
- 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 lane invasions: a collision sensor


## Manual steering

In order to steer manually, you might need to disable sending vehicle control commands within another ROS node.

Therefore the manual control is able to publish to `/vehicle_control_manual_override` ([std_msgs/Bool](http://docs.ros.org/api/std_msgs/html/msg/Bool.html)).

Press `B` to toggle the value.

Note: As sending the vehicle control commands is highly dependent on your setup, you need to implement the subscriber to that topic yourself.

7 changes: 7 additions & 0 deletions carla_manual_control/launch/carla_manual_control.launch
Original file line number Diff line number Diff line change
@@ -0,0 +1,7 @@
<!-- -->
<launch>

<node pkg="carla_manual_control" type="carla_manual_control.py" name="carla_manual_control" output="screen"/>

</launch>

17 changes: 17 additions & 0 deletions carla_manual_control/package.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,17 @@
<?xml version="1.0"?>
<package format="2">
<name>carla_manual_control</name>
<version>0.0.0</version>
<description>The carla_manual_control package</description>
<maintainer email="carla.simulator@gmail.com">CARLA Simulator Team</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>rospy</build_depend>
<build_export_depend>rospy</build_export_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>carla_ros_bridge_msgs</exec_depend>
<exec_depend>sensor_msgs</exec_depend>
<exec_depend>std_msgs</exec_depend>
<export>
</export>
</package>
10 changes: 10 additions & 0 deletions carla_manual_control/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_manual_control'],
package_dir={'': 'src'}
)

setup(**d)

Empty file.
Original file line number Diff line number Diff line change
Expand Up @@ -37,11 +37,11 @@
from std_msgs.msg import Bool
from sensor_msgs.msg import NavSatFix
from sensor_msgs.msg import Image
from carla_ros_bridge.msg import CarlaCollisionEvent # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge.msg import CarlaLaneInvasionEvent # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge_msgs.msg import CarlaCollisionEvent # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge_msgs.msg import CarlaLaneInvasionEvent # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleControl # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleStatus # pylint: disable=no-name-in-module, import-error
from carla_ros_bridge_msgs.msg import CarlaEgoVehicleInfo # pylint: disable=no-name-in-module, import-error

try:
import pygame
Expand Down Expand Up @@ -277,9 +277,12 @@ def __init__(self, width, height):
"/carla/ego_vehicle/vehicle_info", CarlaEgoVehicleInfo, self.vehicle_info_updated)
self.latitude = 0
self.longitude = 0
self.manual_control = False
self.gnss_subscriber = rospy.Subscriber(
"/carla/ego_vehicle/gnss/front/gnss", NavSatFix, self.gnss_updated)
"/carla/ego_vehicle/gnss/gnss1/fix", NavSatFix, self.gnss_updated)
self.tf_listener = tf.TransformListener()
self.manual_control_subscriber = rospy.Subscriber(
"/vehicle_control_manual_override", Bool, self.manual_control_override_updated)

def __del__(self):
self.gnss_subscriber.unregister()
Expand All @@ -292,6 +295,13 @@ def tick(self, clock):
"""
self._notifications.tick(clock)

def manual_control_override_updated(self, data):
"""
Callback on vehicle status updates
"""
self.manual_control = data.data
self.update_info_text()

def vehicle_status_updated(self, vehicle_status):
"""
Callback on vehicle status updates
Expand Down Expand Up @@ -356,7 +366,9 @@ def update_info_text(self):
('Hand brake:', self.vehicle_status.control.hand_brake),
('Manual:', self.vehicle_status.control.manual_gear_shift),
'Gear: %s' % {-1: 'R', 0: 'N'}.get(self.vehicle_status.control.gear,
self.vehicle_status.control.gear)]
self.vehicle_status.control.gear),
'']
self._info_text += [('Manual ctrl:', self.manual_control)]

def toggle_info(self):
"""
Expand Down Expand Up @@ -506,7 +518,7 @@ def main():
"""
main function
"""
rospy.init_node('carla_ros_manual_control')
rospy.init_node('carla_manual_control')

# resolution should be similar to spawned camera with role-name 'view'
resolution = {"width": 800, "height": 600}
Expand Down
18 changes: 0 additions & 18 deletions carla_ros_bridge/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -3,7 +3,6 @@ project(carla_ros_bridge)

## Find catkin macros and libraries
find_package(catkin REQUIRED COMPONENTS
message_generation
rospy
sensor_msgs
geometry_msgs
Expand All @@ -13,23 +12,6 @@ find_package(catkin REQUIRED COMPONENTS

catkin_python_setup()

add_message_files(
FILES
CarlaEgoVehicleControl.msg
CarlaEgoVehicleStatus.msg
CarlaEgoVehicleInfoWheel.msg
CarlaEgoVehicleInfo.msg
CarlaCollisionEvent.msg
CarlaLaneInvasionEvent.msg
)

generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
)


catkin_package()


Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -2,5 +2,5 @@
<launch>
<include file="$(find carla_ros_bridge)/launch/carla_ros_bridge.launch" pass_all_args="True"/>
<include file="$(find carla_ego_vehicle)/launch/carla_example_ego_vehicle.launch" pass_all_args="True"/>
<include file="$(find carla_ego_vehicle)/launch/carla_ros_manual_control.launch" pass_all_args="True"/>
<include file="$(find carla_manual_control)/launch/carla_manual_control.launch" pass_all_args="True"/>
</launch>
Loading

0 comments on commit 71e6ffa

Please sign in to comment.