Skip to content
  •  
  •  
  •  
74 changes: 60 additions & 14 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -33,36 +33,82 @@ set (top_level_source_dir "${CMAKE_CURRENT_SOURCE_DIR}/")

connextdds_sanitize_library_language(LANG ${LANG} VAR lang_var)

add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/action_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/action_tutorials_interfaces")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/actionlib_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/builtin_interfaces")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/composition_interfaces")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/diagnostic_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/example_interfaces")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/gazebo_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/geometry_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/lgsvl_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/libstatistics_collector")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/lifecycle_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/logging_demo")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/map_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/move_base_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/nav_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/pendulum_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rcl_interfaces")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rclcpp")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rmw_dds_common")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rosgraph_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rosidl_generator_py")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/rqt_py_common")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/sensor_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/shape_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/statistics_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/std_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/std_srvs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/stereo_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/test_communication")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/test_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/test_rclcpp")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/tf2_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/trajectory_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/turtlesim")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/unique_identifier_msgs")
add_subdirectory("${CMAKE_CURRENT_SOURCE_DIR}/visualization_msgs")

add_library(RosDataTypes
$<TARGET_OBJECTS:diagnosticlibrary>
$<TARGET_OBJECTS:gazebolibrary>
$<TARGET_OBJECTS:geometrylibrary>
$<TARGET_OBJECTS:lifecyclelibrary>
$<TARGET_OBJECTS:navlibrary>
$<TARGET_OBJECTS:pendulumlibrary>
$<TARGET_OBJECTS:sensorlibrary>
$<TARGET_OBJECTS:shapelibrary>
$<TARGET_OBJECTS:stdlibrary>
$<TARGET_OBJECTS:stereolibrary>
$<TARGET_OBJECTS:testlibrary>
$<TARGET_OBJECTS:tf2library>
$<TARGET_OBJECTS:trajectorylibrary>
$<TARGET_OBJECTS:visualizationlibrary>
$<TARGET_OBJECTS:actionmsgslibrary>
$<TARGET_OBJECTS:actiontutorialsinterfaceslibrary>
$<TARGET_OBJECTS:actionlibmsgslibrary>
$<TARGET_OBJECTS:builtininterfaceslibrary>
$<TARGET_OBJECTS:compositioninterfaceslibrary>
$<TARGET_OBJECTS:diagnosticmsgslibrary>
$<TARGET_OBJECTS:exampleinterfaceslibrary>
$<TARGET_OBJECTS:gazebomsgslibrary>
$<TARGET_OBJECTS:geometrymsgslibrary>
$<TARGET_OBJECTS:lgsvlmsgslibrary>
$<TARGET_OBJECTS:libstatisticscollectorlibrary>
$<TARGET_OBJECTS:lifecyclemsgslibrary>
$<TARGET_OBJECTS:loggingdemolibrary>
$<TARGET_OBJECTS:mapmsgslibrary>
$<TARGET_OBJECTS:movebasemsgslibrary>
$<TARGET_OBJECTS:navmsgslibrary>
$<TARGET_OBJECTS:pendulummsgslibrary>
$<TARGET_OBJECTS:rclinterfaceslibrary>
$<TARGET_OBJECTS:rclcpplibrary>
$<TARGET_OBJECTS:rmwddscommonlibrary>
$<TARGET_OBJECTS:rosgraphmsgslibrary>
$<TARGET_OBJECTS:rosidlgeneratorpylibrary>
$<TARGET_OBJECTS:rqtpycommonlibrary>
$<TARGET_OBJECTS:sensormsgslibrary>
$<TARGET_OBJECTS:shapemsgslibrary>
$<TARGET_OBJECTS:statisticsmsgslibrary>
$<TARGET_OBJECTS:stdmsgslibrary>
$<TARGET_OBJECTS:stdsrvslibrary>
$<TARGET_OBJECTS:stereomsgslibrary>
$<TARGET_OBJECTS:testcommunicationlibrary>
$<TARGET_OBJECTS:testmsgslibrary>
$<TARGET_OBJECTS:testrclcpplibrary>
$<TARGET_OBJECTS:tf2msgslibrary>
$<TARGET_OBJECTS:trajectorymsgslibrary>
$<TARGET_OBJECTS:turtlesimlibrary>
$<TARGET_OBJECTS:uniqueidentifiermsgslibrary>
$<TARGET_OBJECTS:visualizationmsgslibrary>
)

target_link_libraries(RosDataTypes
Expand Down
76 changes: 70 additions & 6 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -31,6 +31,12 @@ ros-data-types/
For more information on the original ROS 2 common interfaces, please refer to
this [repository](https://github.com/ros2/common_interfaces).

This repository also includes data type definitions for topics that are *ROS2 internal*,
for supporting ROS2 parameters, actions, RCL and RMW, etc., thus enabling non-ROS2
Connext DDS applications full access and interoperability with any ROS2 component,
module, tool, visualizer, etc.


## Building ROS Type Library

The ROS Types repository repository provides a set of CMake files to generate
Expand All @@ -41,14 +47,57 @@ that are required to build DDS applications capable of sending ROS messages.

To generate the library, first run `cmake` from a subfolder. This process will
create all the build constructs (e.g., Makefiles or Visual Studio solutions)
that are required to build the library.
that are required to build the library.
**Be sure to include the Connext DDS installation directory in your path before proceeding**
This can be added to the current command shell by using the `rtisetenv_<arch>` script
included with Connext, such as:

**Linux:**
```sh
~/rti_connext_dds-6.0.1/resource/scripts/rtisetenv_x64Linux4gcc7.3.0.bash
```

**Windows:**
```sh
"C:\Program Files\rti_connext_dds-6.0.1\resource\scripts\rtisetenv_x64Win64VS2017.bat"
```

Windows builds can also benefit from running the `vcvars<option>.bat` script before building,
such as `vcvarsall.bat`, to add Visual Studio to the PATH.


**Run CMake to generate the build files**
```bash
cd ros-data-types
mkdir build; cd build
cmake ..
```

**CMake Options**
Optional arguments may be passed to CMake to control the build or correct errors, including:


**ROS2 unbounded variables**
ROS2 uses UNBOUNDED strings and sequences by default; this library can also be built to use
UNBOUNDED vars by passing the `-DUNBOUNDED_ALL=ON` switch on the command line, as in:
```sh
cmake -DUNBOUNDED_ALL=ON ..
```

**RTI Connext Target Type**
If your RTI Connext installation includes support for multiple target platform types, a
specific target may be specified by adding the `-DCONNEXTDDS_ARCH=<arch>` switch, where
`<arch>` is set to your desired build target, such as `x64Linux4gcc7.3.0`, `x64Win64VS2017`, etc.


**Debug or Release Build**
DEBUG build is enabled by default. To build for RELEASE, use the parameter `CMAKE_BUILD_TYPE=Release`
definition as part of your `cmake` invocation, as in:
```sh
cmake -DCMAKE_BUILD_TYPE=Release ..
```

**Language**
By default, the project will generate a type library for C++11. If you want to
generate a type library for a different language, use the the parameter `LANG`
as part of your `cmake` invocation:
Expand All @@ -57,18 +106,33 @@ as part of your `cmake` invocation:
cmake -DLANG=<C|C++|C++11> ..
```

### Building Type Library
These CMake arguments shall be combined into a single command line, as in:
```sh
cmake -DCMAKE_BUILD_TYPE=Release -DUNBOUNDED_ALL=ON ..
```


Next, run the created build constructs. On Unix, that implies using GNU `make`:
### Building the Type Library

Next, run the created build constructs. On **Unix**, that implies using GNU `make`:

```bash
make
```

(On Windows, you will need to build the generated Visual Studio solution
instead.)
On **Windows**, you will need to build the generated Visual Studio solution instead:

```sh
msbuild ros-types.sln </Flags>
```
or:
```sh
devenv ros-types.sln
```
to launch the Visual Studio IDE


### Installing Type Library
### Installing the Type Library

If you want to copy the resulting library and header files to a different
location, run `cmake` and specify the destination directory:
Expand Down
112 changes: 112 additions & 0 deletions _utilities/2_idl_to_tree.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,112 @@
# 2_idl_to_tree.py - Step 2 helper to convert a merged IDL file
# with 1-def-per-line into a directory tree of IDL files.
# Started 2020Nov08 Neil Puthuff

import sys
import os

file_header = '''/*
* Copyright 2012-2018 Open Source Robotics Foundation
*
* Licensed under the Apache License, Version 2.0 (the "License");
* you may not use this file except in compliance with the License.
* You may obtain a copy of the License at
*
* http://www.apache.org/licenses/LICENSE-2.0
*
* Unless required by applicable law or agreed to in writing, software
* distributed under the License is distributed on an "AS IS" BASIS,
* WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
* See the License for the specific language governing permissions and
* limitations under the License.
*/
'''

def add_fmt(iline):
oline = ""
indent = 0
skip = False
for c in iline:
if skip == True:
if c != ' ':
if c == '}':
indent -= 2
oline = oline + (" " * indent) + c
skip = False
elif c == '{':
indent += 2
oline = oline + c + '\n'
skip = True
elif c == ';':
oline = oline + c + '\n'
skip = True
else:
oline = oline + c
return oline

with open(sys.argv[1], 'r') as idl_in:
line_in = idl_in.readline()
type_cnt = 1
while line_in:
modName = ''
subDir = ''
typeName = ''
includeFiles = set()
wlist = line_in.split()
if wlist[0] == "module":
modName = wlist[1]
if wlist[3] == "module":
subDir = wlist[4]

wcnt = 0
for w in wlist:
if w == "struct":
typeName = wlist[wcnt+1].rstrip('_')
wcnt += 1

if "::" in w:
tmpW = w
if "sequence<" in tmpW:
tmpW = tmpW[9:].strip(">")
if "," in tmpW:
tmpW = tmpW[0:tmpW.rfind(',')-1]
incParts = tmpW.split('::')
incFile = "{}/{}/{}.idl".format(incParts[0], incParts[1], incParts[3].rstrip('_'))
includeFiles.add(incFile)

type_cnt += 1

# create directories if they don't already exist
if not os.path.exists('./{}'.format(modName)):
os.makedirs('./{}'.format(modName))
if not os.path.exists('./{}/{}'.format(modName, subDir)):
os.makedirs('./{}/{}'.format(modName, subDir))

# create the IDL type file
f_idl = open('./{}/{}/{}.idl'.format(modName, subDir, typeName), "w")

# write the file comment header
f_idl.write("{}\n".format(file_header))

# make the ifndef string
ifndef_string = "__{}__{}__{}__idl".format(modName, subDir, typeName)
f_idl.write("#ifndef {}\n".format(ifndef_string))
f_idl.write("#define {}\n\n".format(ifndef_string))

# add any include files needed
if len(includeFiles) > 0:
for incF in includeFiles:
f_idl.write("#include \"{}\"\n".format(incF))
f_idl.write("\n")

# write the data types info
f_idl.write("{}\n".format(add_fmt(line_in)))

# close the ifndef string
f_idl.write("#endif // {}\n".format(ifndef_string))

f_idl.close()

line_in = idl_in.readline()
idl_in.close()

Loading