Skip to content

Commit

Permalink
Merge pull request #8 from carla-simulator/feature/ros_bridge_api_v0.9
Browse files Browse the repository at this point in the history
Feature/ros bridge api v0.9
  • Loading branch information
nsubiron authored Dec 14, 2018
2 parents 47600df + 51f97c9 commit 4d125d5
Show file tree
Hide file tree
Showing 32 changed files with 2,359 additions and 1,271 deletions.
2 changes: 2 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,2 @@
*.pyc
build.gradle
3 changes: 3 additions & 0 deletions .pylintrc
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
[TYPECHECK]
ignored-modules=numpy,carla
disable=logging-format-interpolation,locally-disabled,cyclic-import,too-many-instance-attributes,invalid-name
199 changes: 23 additions & 176 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,200 +1,47 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_ros_bridge)

## Compile as C++11, supported in ROS Kinetic and newer
# add_compile_options(-std=c++11)

## Find catkin macros and libraries
## if COMPONENTS list like find_package(catkin REQUIRED COMPONENTS xyz)
## is used, also find other catkin packages
find_package(catkin REQUIRED COMPONENTS
rospy
sensor_msgs
tf
)

## System dependencies are found with CMake's conventions
# find_package(Boost REQUIRED COMPONENTS system)


## Uncomment this if the package has a setup.py. This macro ensures
## modules and global scripts declared therein get installed
## See http://ros.org/doc/api/catkin/html/user_guide/setup_dot_py.html
catkin_python_setup()

################################################
## Declare ROS messages, services and actions ##
################################################

## To declare and build messages, services or actions from within this
## package, follow these steps:
## * Let MSG_DEP_SET be the set of packages whose message types you use in
## your messages/services/actions (e.g. std_msgs, actionlib_msgs, ...).
## * In the file package.xml:
## * add a build_depend tag for "message_generation"
## * add a build_depend and a run_depend tag for each package in MSG_DEP_SET
## * If MSG_DEP_SET isn't empty the following dependency has been pulled in
## but can be declared for certainty nonetheless:
## * add a run_depend tag for "message_runtime"
## * In this file (CMakeLists.txt):
## * add "message_generation" and every package in MSG_DEP_SET to
## find_package(catkin REQUIRED COMPONENTS ...)
## * add "message_runtime" and every package in MSG_DEP_SET to
## catkin_package(CATKIN_DEPENDS ...)
## * uncomment the add_*_files sections below as needed
## and list every .msg/.srv/.action file to be processed
## * uncomment the generate_messages entry below
## * add every package in MSG_DEP_SET to generate_messages(DEPENDENCIES ...)

## Generate messages in the 'msg' folder
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )

## Generate services in the 'srv' folder
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )

## Generate actions in the 'action' folder
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )

## Generate added messages and services with any dependencies listed here
# generate_messages(
# DEPENDENCIES
# sensor_msgs
# )

################################################
## Declare ROS dynamic reconfigure parameters ##
################################################

## To declare and build dynamic reconfigure parameters within this
## package, follow these steps:
## * In the file package.xml:
## * add a build_depend and a run_depend tag for "dynamic_reconfigure"
## * In this file (CMakeLists.txt):
## * add "dynamic_reconfigure" to
## find_package(catkin REQUIRED COMPONENTS ...)
## * uncomment the "generate_dynamic_reconfigure_options" section below
## and list every .cfg file to be processed

## Generate dynamic reconfigure parameters in the 'cfg' folder
# generate_dynamic_reconfigure_options(
# cfg/DynReconf1.cfg
# cfg/DynReconf2.cfg
# )

###################################
## catkin specific configuration ##
###################################
## The catkin_package macro generates cmake config files for your package
## Declare things to be passed to dependent projects
## INCLUDE_DIRS: uncomment this if your package contains header files
## LIBRARIES: libraries you create in this project that dependent projects also need
## CATKIN_DEPENDS: catkin_packages dependent projects also need
## DEPENDS: system dependencies of this project that dependent projects also need
catkin_package(
# INCLUDE_DIRS include
# LIBRARIES carla_ros_bridge
# CATKIN_DEPENDS rospy sensor_msgs tf
# DEPENDS system_lib
add_message_files(
FILES
CarlaVehicleControl.msg
)

###########
## Build ##
###########

## Specify additional locations of header files
## Your package locations should be listed before other locations
include_directories(
# include
${catkin_INCLUDE_DIRS}
generate_messages(
DEPENDENCIES
sensor_msgs
)

## Declare a C++ library
# add_library(${PROJECT_NAME}
# src/${PROJECT_NAME}/carla_ros_bridge.cpp
# )

## Add cmake target dependencies of the library
## as an example, code may need to be generated before libraries
## either from message generation or dynamic reconfigure
# add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Declare a C++ executable
## With catkin_make all packages are built within a single CMake context
## The recommended prefix ensures that target names across packages don't collide
# add_executable(${PROJECT_NAME}_node src/carla_ros_bridge_node.cpp)

## Rename C++ executable without prefix
## The above recommended prefix causes long target names, the following renames the
## target back to the shorter version for ease of user use
## e.g. "rosrun someones_pkg node" instead of "rosrun someones_pkg someones_pkg_node"
# set_target_properties(${PROJECT_NAME}_node PROPERTIES OUTPUT_NAME node PREFIX "")

## Add cmake target dependencies of the executable
## same as for the library above
# add_dependencies(${PROJECT_NAME}_node ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})

## Specify libraries to link a library or executable target against
# target_link_libraries(${PROJECT_NAME}_node
# ${catkin_LIBRARIES}
# )

#############
## Install ##
#############
catkin_package()

# all install targets should use catkin DESTINATION variables
# See http://ros.org/doc/api/catkin/html/adv_user_guide/variables.html

## Mark executable scripts (Python etc.) for installation
## in contrast to setup.py, you can choose the destination
# install(PROGRAMS
# scripts/my_python_script
# DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )

## Mark executables and/or libraries for installation
# install(TARGETS ${PROJECT_NAME} ${PROJECT_NAME}_node
# ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
# RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
# )
include_directories(
${catkin_INCLUDE_DIRS}
)

## Mark cpp header files for installation
# install(DIRECTORY include/${PROJECT_NAME}/
# DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION}
# FILES_MATCHING PATTERN "*.h"
# PATTERN ".svn" EXCLUDE
# )
install(PROGRAMS
src/carla_ros_bridge/client.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)

## Mark other files for installation (e.g. launch and bag files, etc.)
install(FILES
client.launch
client_with_rviz.launch
test/ros_bridge_client.test
install(FILES
client.launch
client_with_rviz.launch
test/ros_bridge_client.test
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

#############
## Testing ##
#############
)

## Add gtest based cpp test target and link libraries
# catkin_add_gtest(${PROJECT_NAME}-test test/test_carla_ros_bridge.cpp)
# if(TARGET ${PROJECT_NAME}-test)
# target_link_libraries(${PROJECT_NAME}-test ${PROJECT_NAME})
# endif()
install(DIRECTORY
config
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}
)

## Add folders to be run by python nosetests
# catkin_add_nosetests(test)
68 changes: 39 additions & 29 deletions Readme.md
Original file line number Diff line number Diff line change
Expand Up @@ -12,17 +12,13 @@ This ros package aims at providing a simple ros bridge for carla simulator.
# Features

- [x] Cameras (depth, segmentation, rgb) support
- [x] Add camera matrix
- [x] Lidar sensor support
- [x] Transform publications
- [x] Manual control using ackermann msg
- [x] Autopilot mode using rosparam
- [x] Rosbag in the bridge (in order to avoid rosbag recoard -a small time errors)
- [x] Handle ros dependencies
- [x] Marker/bounding box messages for cars/pedestrian
- [X] Lidar sensor support
- [ ] Rosbag in the bridge (in order to avoid rosbag record -a small time errors)
- [ ] Add traffic light support
- [ ] Support dynamic change (restarting simulation using a topic/rosparam)


# Setup

Expand All @@ -39,9 +35,9 @@ This ros package aims at providing a simple ros bridge for carla simulator.
For more information about configuring a ros environment see
http://wiki.ros.org/ROS/Tutorials/InstallingandConfiguringROSEnvironment

## Install carla python client in your workspace
## Install carla python client API in your workspace

cd carla/Deprecated/PythonClient
cd carla/PythonAPI
pip2 install -e . --user --upgrade

Check the installation is successfull by trying to import carla from python:
Expand All @@ -58,9 +54,9 @@ You should see the Success message without any errors.

### Add the carla_ros_bridge in the catkin workspace

Run the following command after replacing [PATH_TO_CARLA] with the actual path to carla directory on your machine:
Run the following command after replacing [PATH_TO_ROS_BRIDGE] with the actual path to carla ros bridge directory on your machine:

ln -s [PATH_TO_CARLA]/carla_ros_bridge/ ~/ros/catkin_ws_for_carla/src/
ln -s [PATH_TO_ROS_BRIDGE]/carla_ros_bridge/ ~/ros/catkin_ws_for_carla/src/
source ~/ros/catkin_ws_for_carla/devel/setup.bash
rosdep update
rosdep install --from-paths ~/ros/catkin_ws_for_carla
Expand All @@ -69,9 +65,9 @@ Run the following command after replacing [PATH_TO_CARLA] with the actual path t
source ~/ros/catkin_ws_for_carla/devel/setup.bash


### Test your installation
### Test your installation (section outdated)

If you use the builded binary (0.8.2):
If you use the builded binary (0.9.1):

./CarlaUE4.sh -carla-server -windowed -ResX=320 -ResY=240

Expand Down Expand Up @@ -113,44 +109,58 @@ To start the ros bridge with rviz use:

roslaunch carla_ros_bridge client_with_rviz.launch

You can setup the wanted camera/sensors in config/settings.yaml.

# Autopilot control

To enable autopilot control set the ros param carla_autopilot to True

rosparam set carla_autopilot True
You can setup the vehicle wanted to used as ego vehicle in config/settings.yaml.

# Manual control
Then you can make use of the CARLA python API scripts manual_control.py. This spawns a vehicle with role_name='hero' which is interpreted
as the ego vehicle as defined by the config/settings.yaml.

To enable manual control set the ros param carla_autopilot to False
You can then further spawn other vehicles using spawn_npc.py from CARLA python API. Then those vehicles will show up also on ROS side.

rosparam set carla_autopilot False


Then you can send command to the car using the /ackermann_cmd topic.
# Test control messages
You can send command to the car using the /carla/ego_vehicle/ackermann_cmd topic.

Example of forward movements, speed in in meters/sec.

rostopic pub /ackermann_cmd ackermann_msgs/AckermannDrive "{steering_angle: 0.0, steering_angle_velocity: 0.0, speed: 10, acceleration: 0.0,
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


Example of forward with steering

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

Warning: the steering_angle is the driving angle (in radians) not the wheel angle, for now max wheel is set to 500 degrees.


Example for backward :

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

# Test sensor messages

## Object information

### Ego vehicle

The ego vehicle status is provided via the topic /carla/ego_vehicle/odometry (nav_msgs.Odometry)

### Other vehicles

The other vehicles data is provided via the 'ideal' object list /carla/objects (derived_object_msgs.ObjectArray)

## Map information

The OPEN Drive map description is published via /map topic (std_msgs.String)

## Sensor information

### Ego vehicle
The ego Vehicle sensors are provided via topics with prefix /carla/ego_vehicle/<sensor_topic>


# ROSBAG recording
# ROSBAG recording (not yet tested)

The carla_ros_bridge could also be used to record all published topics into a rosbag:

Expand Down
3 changes: 3 additions & 0 deletions check.sh
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
#!/bin/bash
autopep8 src/carla_ros_bridge/*.py --in-place --max-line-length=100
pylint --rcfile=.pylintrc src/carla_ros_bridge/
2 changes: 0 additions & 2 deletions client.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,5 @@
<arg name='rosbag_fname' default=''/>
<param name="rosbag_fname" value="$(arg rosbag_fname)"/>
<rosparam file="$(find carla_ros_bridge)/config/settings.yaml" command="load" />
<param name="carla_autopilot" type="boolean" value="True" />
<param name="curr_episode" type="string" value="" />
<node pkg="carla_ros_bridge" name="carla_ros_bridge" type="client.py" output="screen"/>
</launch>
1 change: 0 additions & 1 deletion client_with_rviz.launch
Original file line number Diff line number Diff line change
@@ -1,5 +1,4 @@
<launch>
<include file="$(find carla_ros_bridge)/client.launch" pass_all_args="True"/>
<param name ="/use_sim_time" value="true"/>
<node pkg="rviz" type="rviz" name="rviz" args="-d $(find carla_ros_bridge)/config/carla_default_rviz.cfg.rviz"/>
</launch>
Loading

0 comments on commit 4d125d5

Please sign in to comment.