Skip to content

Commit

Permalink
Merge pull request #20 from carla-simulator/ros2
Browse files Browse the repository at this point in the history
[ROS2] Hybrid ROS1/ROS2
  • Loading branch information
joel-mb authored Mar 22, 2021
2 parents 4857d81 + 51c7663 commit 081fdcd
Show file tree
Hide file tree
Showing 8 changed files with 138 additions and 70 deletions.
150 changes: 96 additions & 54 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,57 +1,99 @@
cmake_minimum_required(VERSION 2.8.3)
project(carla_msgs)

## Find catkin macros and libraries
find_package(catkin REQUIRED COMPONENTS
message_generation
std_msgs
geometry_msgs
diagnostic_msgs
)

add_service_files(
DIRECTORY srv
FILES
SpawnObject.srv
DestroyObject.srv
GetBlueprints.srv
)

add_message_files(
DIRECTORY msg
FILES
CarlaBoundingBox.msg
CarlaEgoVehicleControl.msg
CarlaEgoVehicleStatus.msg
CarlaEgoVehicleInfoWheel.msg
CarlaEgoVehicleInfo.msg
CarlaCollisionEvent.msg
CarlaLaneInvasionEvent.msg
CarlaWorldInfo.msg
CarlaActorInfo.msg
CarlaActorList.msg
CarlaControl.msg
CarlaStatus.msg
CarlaTrafficLightInfo.msg
CarlaTrafficLightInfoList.msg
CarlaTrafficLightStatus.msg
CarlaTrafficLightStatusList.msg
CarlaWalkerControl.msg
CarlaWeatherParameters.msg
)

generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
diagnostic_msgs
)


catkin_package(
CATKIN_DEPENDS
message_runtime
std_msgs
geometry_msgs
diagnostic_msgs
)
find_package(ros_environment REQUIRED)

set(ROS_VERSION $ENV{ROS_VERSION})

set(SERVICE_FILES SpawnObject.srv DestroyObject.srv GetBlueprints.srv)

set(MSG_FILES
CarlaBoundingBox.msg
CarlaEgoVehicleControl.msg
CarlaEgoVehicleStatus.msg
CarlaEgoVehicleInfoWheel.msg
CarlaEgoVehicleInfo.msg
CarlaCollisionEvent.msg
CarlaLaneInvasionEvent.msg
CarlaWorldInfo.msg
CarlaActorInfo.msg
CarlaActorList.msg
CarlaControl.msg
CarlaStatus.msg
CarlaTrafficLightInfo.msg
CarlaTrafficLightInfoList.msg
CarlaTrafficLightStatus.msg
CarlaTrafficLightStatusList.msg
CarlaWalkerControl.msg
CarlaWeatherParameters.msg)

if(${ROS_VERSION} EQUAL 1)
cmake_minimum_required(VERSION 2.8.3)

# Find catkin macros and libraries
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs
geometry_msgs diagnostic_msgs)

add_service_files(DIRECTORY srv FILES ${SERVICE_FILES})

add_message_files(DIRECTORY msg FILES ${MSG_FILES})

generate_messages(DEPENDENCIES std_msgs geometry_msgs diagnostic_msgs)

catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs diagnostic_msgs)

elseif(${ROS_VERSION} EQUAL 2)

cmake_minimum_required(VERSION 3.5)

if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD_REQUIRED ON)
set(CMAKE_CXX_STANDARD 14)
endif()

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
add_compile_options(-Wall -Wextra -Wpedantic)
endif()

find_package(ament_cmake REQUIRED)
find_package(builtin_interfaces REQUIRED)
find_package(std_msgs REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(diagnostic_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

# Apend "msg/" to each file name
set(TEMP_LIST "")
foreach(MSG_FILE ${MSG_FILES})
list(APPEND TEMP_LIST "msg/${MSG_FILE}")
endforeach()
set(MSG_FILES ${TEMP_LIST})

# Apend "srv/" to each file name
set(TEMP_LIST "")
foreach(SERVICE_FILE ${SERVICE_FILES})
list(APPEND TEMP_LIST "srv/${SERVICE_FILE}")
endforeach()
set(SERVICE_FILES ${TEMP_LIST})

rosidl_generate_interfaces(
${PROJECT_NAME}
${MSG_FILES}
${SERVICE_FILES}
DEPENDENCIES
builtin_interfaces
std_msgs
geometry_msgs
diagnostic_msgs
ADD_LINTER_TESTS)

ament_export_dependencies(rosidl_default_runtime)

if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
ament_lint_auto_find_test_dependencies()
endif()

ament_package()

endif()
5 changes: 5 additions & 0 deletions CONTRIBUTING.md
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
Contributing to CARLA
=====================

We are more than happy to accept contributions!

2 changes: 1 addition & 1 deletion msg/CarlaCollisionEvent.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#
# A collision event

Header header
std_msgs/Header header

uint32 other_actor_id
geometry_msgs/Vector3 normal_impulse
2 changes: 1 addition & 1 deletion msg/CarlaEgoVehicleControl.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#
# This represents a vehicle control message sent to CARLA simulator

Header header
std_msgs/Header header

# The CARLA vehicle control data

Expand Down
2 changes: 1 addition & 1 deletion msg/CarlaEgoVehicleStatus.msg
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
# For a copy, see <https://opensource.org/licenses/MIT>.
#

Header header
std_msgs/Header header

float32 velocity
geometry_msgs/Accel acceleration
Expand Down
2 changes: 1 addition & 1 deletion msg/CarlaLaneInvasionEvent.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@
#
# A lane invasion event

Header header
std_msgs/Header header

int32[] crossed_lane_markings

Expand Down
43 changes: 32 additions & 11 deletions package.xml
Original file line number Diff line number Diff line change
@@ -1,17 +1,38 @@
<?xml version="1.0"?>
<package>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>carla_msgs</name>
<version>1.2.0</version>
<version>1.3.0</version>
<description>The carla_msgs package</description>
<maintainer email="carla.simulator@gmail.com">CARLA Simulator Team</maintainer>
<license>MIT</license>
<buildtool_depend>catkin</buildtool_depend>
<build_depend>message_generation</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_msgs</build_depend>
<build_depend>diagnostic_msgs</build_depend>
<run_depend>message_runtime</run_depend>
<run_depend>std_msgs</run_depend>
<run_depend>geometry_msgs</run_depend>
<run_depend>diagnostic_msgs</run_depend>
<url type="website">http://carla.org/</url>
<url type="repository">https://github.com/carla-simulator/ros-carla-msgs</url>
<url type="bugtracker">https://github.com/carla-simulator/ros-carla-msgs/issues</url>
<author email="carla.simulator@gmail.com">CARLA Simulator Team</author>

<buildtool_depend condition="$ROS_VERSION == 1">catkin</buildtool_depend>
<buildtool_depend condition="$ROS_VERSION == 2">ament_cmake</buildtool_depend>

<build_depend condition="$ROS_VERSION == 1">message_generation</build_depend>
<build_depend condition="$ROS_VERSION == 2">rosidl_default_generators</build_depend>
<build_depend>ros_environment</build_depend>

<depend condition="$ROS_VERSION == 2">builtin_interfaces</depend>
<depend>std_msgs</depend>
<depend>geometry_msgs</depend>
<depend>diagnostic_msgs</depend>

<exec_depend condition="$ROS_VERSION == 1">message_runtime</exec_depend>
<exec_depend condition="$ROS_VERSION == 2">rosidl_default_runtime</exec_depend>

<test_depend condition="$ROS_VERSION == 2">ament_lint_auto</test_depend>
<test_depend condition="$ROS_VERSION == 2">ament_lint_common</test_depend>

<member_of_group>rosidl_interface_packages</member_of_group>

<export>
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
</export>
</package>
2 changes: 1 addition & 1 deletion srv/DestroyObject.srv
Original file line number Diff line number Diff line change
Expand Up @@ -7,4 +7,4 @@

int32 id
---
bool success
bool success

0 comments on commit 081fdcd

Please sign in to comment.