Skip to content

Commit

Permalink
Add CaralV2XCustom* messages
Browse files Browse the repository at this point in the history
  • Loading branch information
berndgassmann committed Jun 14, 2024
1 parent 8075186 commit 5549dcd
Show file tree
Hide file tree
Showing 4 changed files with 36 additions and 2 deletions.
9 changes: 7 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -29,6 +29,9 @@ set(MSG_FILES
CarlaTrafficLightStatus.msg
CarlaTrafficLightStatusList.msg
CarlaSynchronizationWindow.msg
CarlaV2XCustomData.msg
CarlaV2XCustomDataList.msg
CarlaV2XCustomMessage.msg
CarlaWalkerControl.msg
CarlaWeatherParameters.msg)

Expand All @@ -37,15 +40,15 @@ if(${ROS_VERSION} EQUAL 1)

# Find catkin macros and libraries
find_package(catkin REQUIRED COMPONENTS message_generation std_msgs
geometry_msgs diagnostic_msgs shape_msgs ackermann_msgs)
geometry_msgs diagnostic_msgs shape_msgs ackermann_msgs etsi_its_cam_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 shape_msgs ackermann_msgs)
catkin_package(CATKIN_DEPENDS message_runtime std_msgs geometry_msgs diagnostic_msgs shape_msgs ackermann_msgs etsi_its_cam_msgs)

elseif(${ROS_VERSION} EQUAL 2)

Expand All @@ -67,6 +70,7 @@ elseif(${ROS_VERSION} EQUAL 2)
find_package(geometry_msgs REQUIRED)
find_package(ackermann_msgs REQUIRED)
find_package(diagnostic_msgs REQUIRED)
find_package(etsi_its_cam_msgs REQUIRED)
find_package(rosidl_default_generators REQUIRED)

# Apend "msg/" to each file name
Expand Down Expand Up @@ -94,6 +98,7 @@ elseif(${ROS_VERSION} EQUAL 2)
geometry_msgs
ackermann_msgs
diagnostic_msgs
etsi_its_cam_msgs
ADD_LINTER_TESTS)

ament_export_dependencies(rosidl_default_runtime)
Expand Down
10 changes: 10 additions & 0 deletions msg/CarlaV2XCustomData.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#
# Copyright (c) 2024 Intel Corporation.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
#

float32 power
carla_msgs/CarlaV2XCustomMessage message

9 changes: 9 additions & 0 deletions msg/CarlaV2XCustomDataList.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
#
# Copyright (c) 2024 Intel Corporation.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
#

carla_msgs/CarlaV2XCustomData[] data

10 changes: 10 additions & 0 deletions msg/CarlaV2XCustomMessage.msg
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
#
# Copyright (c) 2024 Intel Corporation.
#
# This work is licensed under the terms of the MIT license.
# For a copy, see <https://opensource.org/licenses/MIT>.
#

etsi_its_cam_msgs/ItsPduHeader header
string data

0 comments on commit 5549dcd

Please sign in to comment.