Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

ROS1/ROS2 Hybrid Packages #15

Merged
merged 5 commits into from
Nov 20, 2019
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
29 changes: 29 additions & 0 deletions .circleci/config.yml
Original file line number Diff line number Diff line change
Expand Up @@ -56,9 +56,38 @@ jobs:
catkin_test_results
working_directory: ~/src

dashing:
docker:
- image: autonomoustuff/docker-builds:dashing-ros-base
steps:
- checkout
- run:
name: Set Up Container
command: |
apt-get update -qq
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
rosdep update
rosdep install --from-paths . --ignore-src -y
cd ..
- run:
name: Build
command: |
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
cd ..
colcon build
- run:
name: Run Tests
command: |
source `find /opt/ros -maxdepth 2 -name local_setup.bash | sort | head -1`
cd ..
colcon build
colcon test-result
working_directory: ~/src

workflows:
version: 2
ros_build:
jobs:
- kinetic
- melodic
- dashing
15 changes: 12 additions & 3 deletions automotive_autonomy_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,4 +1,13 @@
cmake_minimum_required(VERSION 2.8.3)
project(automotive_autonomy_msgs)
find_package(catkin REQUIRED)
catkin_metapackage()

set(ROS_VERSION $ENV{ROS_VERSION})

if(${ROS_VERSION} EQUAL 1)
cmake_minimum_required(VERSION 2.8.3)
find_package(catkin REQUIRED)
catkin_package()
elseif(${ROS_VERSION} EQUAL 2)
cmake_minimum_required(VERSION 3.5)
find_package(ament_cmake REQUIRED)
ament_package()
endif()
13 changes: 7 additions & 6 deletions automotive_autonomy_msgs/package.xml
Original file line number Diff line number Diff line change
@@ -1,24 +1,25 @@
<?xml version="1.0"?>
<package format="2">
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>automotive_autonomy_msgs</name>
<version>2.0.3</version>
<description>Messages for vehicle automation</description>
<maintainer email="software@autonomoustuff.com">AutonomouStuff Software Development Team</maintainer>
<license>MIT</license>

<url type="website">http://github.com/automotive_autonomy_msgs</url>
<url type="repository">https://github.com/astuff/automotive_autonomy_msgs</url>
<url type="bugtracker">https://github.com/astuff/automotive_autonomy_msgs/issues</url>

<maintainer email="software@autonomoustuff.com">AutonomouStuff Software Development Team</maintainer>
<author email="dstanek@autonomoustuff.com">Daniel Stanek</author>
<author email="jwhitley@autonomoustuff.com">Joshua Whitley</author>

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

<exec_depend>automotive_navigation_msgs</exec_depend>
<exec_depend>automotive_platform_msgs</exec_depend>

<export>
<metapackage />
<build_type condition="$ROS_VERSION == 1">catkin</build_type>
<build_type condition="$ROS_VERSION == 2">ament_cmake</build_type>
</export>
</package>
121 changes: 88 additions & 33 deletions automotive_navigation_msgs/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,41 +1,96 @@
cmake_minimum_required(VERSION 2.8.3)
project(automotive_navigation_msgs)

find_package(catkin REQUIRED
COMPONENTS
message_generation
std_msgs
geometry_msgs
)
set(ROS_VERSION $ENV{ROS_VERSION})

## Declare ROS messages and services
add_message_files(DIRECTORY msg FILES
CommandWithHandshake.msg
DesiredDestination.msg
Direction.msg
DistanceToDestination.msg
LaneBoundary.msg
LaneBoundaryArray.msg
ModuleState.msg
PointOfInterestArray.msg
PointOfInterest.msg
PointOfInterestRequest.msg
PointOfInterestResponse.msg
PointOfInterestStatus.msg
RoadNetworkBoundaries.msg
set(MSG_FILES
"CommandWithHandshake.msg"
"DesiredDestination.msg"
"Direction.msg"
"DistanceToDestination.msg"
"LaneBoundary.msg"
"LaneBoundaryArray.msg"
"ModuleState.msg"
"PointOfInterestArray.msg"
"PointOfInterest.msg"
"PointOfInterestRequest.msg"
"PointOfInterestResponse.msg"
"PointOfInterestStatus.msg"
"RoadNetworkBoundaries.msg"
)

add_service_files(DIRECTORY srv FILES
GetImageForMapTile.srv
)
if(${ROS_VERSION} EQUAL 1)

## Generate added messages and services
generate_messages(DEPENDENCIES std_msgs geometry_msgs)
cmake_minimum_required(VERSION 2.8.3)

## Declare a catkin package
catkin_package(CATKIN_DEPENDS
message_runtime
std_msgs
geometry_msgs
)
find_package(catkin REQUIRED
COMPONENTS
message_generation
std_msgs
geometry_msgs
)

## Declare ROS messages and services
add_message_files(DIRECTORY msg FILES
${MSG_FILES}
DIRECTORY msg
)

add_service_files(DIRECTORY srv FILES
GetImageForMapTile.srv
)

## Generate added messages and services
generate_messages(DEPENDENCIES std_msgs geometry_msgs)

## Declare a catkin package
catkin_package(CATKIN_DEPENDS
message_runtime
std_msgs
geometry_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(geometry_msgs REQUIRED)
find_package(std_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})

rosidl_generate_interfaces(${PROJECT_NAME}
${MSG_FILES}
DEPENDENCIES
builtin_interfaces
geometry_msgs
std_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()
103 changes: 103 additions & 0 deletions automotive_navigation_msgs/migration/PointOfInterestRequest.bmr
Original file line number Diff line number Diff line change
@@ -0,0 +1,103 @@
class update_automotive_navigation_msgs_PointOfInterestRequest_32ddedb83d8866a4c42724a85ecf2c80(MessageUpdateRule):
old_type = "automotive_navigation_msgs/PointOfInterestRequest"
old_full_text = """
# Point of Interest Request Message
# Contains information needed to request point of interest information

std_msgs/Header header

string name # Name of the point of interest list

string module_name # module name of the requesting node

uint16 requestId # Unique id of this request
# Can make another request with the same requestId and
# different update_num, guid, or tolerance. New one will
# replace the old one.

uint16 cancel # Set to 1 to cancel the request with this requestId

uint16 update_num # The update number of the point list to use

uint16 guid_valid # Request is for a specific point, not all points in list
uint64 guid # The unique Id for the desired point

float32 tolerance # How close to the current vehicle's position a point needs to be


================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data
# in a particular coordinate frame.
#
# sequence ID: consecutively increasing ID
uint32 seq
#Two-integer timestamp that is expressed as:
# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
# time-handling sugar is provided by the client library
time stamp
#Frame this data is associated with
string frame_id
"""

new_type = "automotive_navigation_msgs/PointOfInterestRequest"
new_full_text = """
# Point of Interest Request Message
# Contains information needed to request point of interest information

std_msgs/Header header

string name # Name of the point of interest list

string module_name # module name of the requesting node

uint16 request_id # Unique id of this request
# Can make another request with the same requestId and
# different update_num, guid, or tolerance. New one will
# replace the old one.

uint16 cancel # Set to 1 to cancel the request with this requestId

uint16 update_num # The update number of the point list to use

uint16 guid_valid # Request is for a specific point, not all points in list
uint64 guid # The unique Id for the desired point

float32 tolerance # How close to the current vehicle's position a point needs to be


================================================================================
MSG: std_msgs/Header
# Standard metadata for higher-level stamped data types.
# This is generally used to communicate timestamped data
# in a particular coordinate frame.
#
# sequence ID: consecutively increasing ID
uint32 seq
#Two-integer timestamp that is expressed as:
# * stamp.sec: seconds (stamp_secs) since epoch (in Python the variable is called 'secs')
# * stamp.nsec: nanoseconds since stamp_secs (in Python the variable is called 'nsecs')
# time-handling sugar is provided by the client library
time stamp
#Frame this data is associated with
string frame_id
"""

order = 0
migrated_types = [
("Header","Header"),]

valid = True

def update(self, old_msg, new_msg):
self.migrate(old_msg.header, new_msg.header)
new_msg.name = old_msg.name
new_msg.module_name = old_msg.module_name
new_msg.request_id = old_msg.requestId
new_msg.cancel = old_msg.cancel
new_msg.update_num = old_msg.update_num
new_msg.guid_valid = old_msg.guid_valid
new_msg.guid = old_msg.guid
new_msg.tolerance = old_msg.tolerance