Skip to content

Commit

Permalink
ROS2 port (#13)
Browse files Browse the repository at this point in the history
* Initial ROS2 port

Co-authored-by: Pranay Mathur <[email protected]>
  • Loading branch information
nkhedekar and Matnay authored Sep 11, 2020
1 parent 17bcb59 commit f455edd
Show file tree
Hide file tree
Showing 8 changed files with 287 additions and 213 deletions.
76 changes: 47 additions & 29 deletions open3d_conversions/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,44 +1,62 @@
cmake_minimum_required(VERSION 3.5.0)
cmake_minimum_required(VERSION 3.5)
project(open3d_conversions)

find_package(catkin REQUIRED COMPONENTS
roscpp
sensor_msgs
)
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()

# system dependencies
find_package(ament_cmake REQUIRED)
find_package(ament_cmake_ros REQUIRED)
find_package(Eigen3 REQUIRED)
find_package(Open3D REQUIRED)

catkin_package(
INCLUDE_DIRS include
LIBRARIES open3d_conversions
CATKIN_DEPENDS roscpp sensor_msgs
DEPENDS EIGEN3 Open3D
)
find_package(rclcpp REQUIRED)
find_package(sensor_msgs REQUIRED)

include_directories(
include
${catkin_INCLUDE_DIRS}
${EIGEN3_INCLUDE_DIR}
${Open3D_INCLUDE_DIRS}
)

# C++ library
add_library(open3d_conversions src/open3d_conversions.cpp)
add_dependencies(open3d_conversions ${open3d_conversions_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
target_link_libraries(open3d_conversions ${catkin_LIBRARIES} ${Open3D_LIBRARIES})

# Install
install(TARGETS open3d_conversions
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_GLOBAL_BIN_DESTINATION})

install(DIRECTORY include/open3d_conversions/
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION})

# Tests
if (CATKIN_ENABLE_TESTING)
catkin_add_gtest(test_open3d_conversions test/test_open3d_conversions.cpp)
target_link_libraries(test_open3d_conversions open3d_conversions ${catkin_LIBRARIES} ${Open3D_LIBRARIES})
target_include_directories(open3d_conversions PUBLIC
$<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}/include>
$<INSTALL_INTERFACE:include>)
ament_target_dependencies(
open3d_conversions
"rclcpp"
"sensor_msgs"
)
target_link_libraries(open3d_conversions ${Open3D_LIBRARIES})
target_compile_definitions(open3d_conversions PUBLIC "OPEN3D_CONVERSIONS_BUILDING_LIBRARY")

install(
DIRECTORY include/
DESTINATION include
)
install(
TARGETS open3d_conversions
EXPORT export_${PROJECT_NAME}
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin
INCLUDES DESTINATION include
)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
find_package(ament_lint_auto REQUIRED)
ament_add_gtest(test_open3d_conversions test/test_open3d_conversions.cpp)
target_link_libraries(test_open3d_conversions open3d_conversions ${Open3D_LIBRARIES})
ament_lint_auto_find_test_dependencies()
endif()

ament_export_include_directories(include)
ament_export_libraries(open3d_conversions)
ament_export_targets(export_${PROJECT_NAME})
ament_export_dependencies(Open3D rclcpp)

ament_package()
6 changes: 3 additions & 3 deletions open3d_conversions/README.md
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ This package provides functions that can convert pointclouds from ROS to Open3D

## System Requirements

* Ubuntu 18.04+: GCC 5+
* Ubuntu 20.04+: GCC 5+

## Installation

Expand All @@ -26,9 +26,9 @@ This package provides functions that can convert pointclouds from ROS to Open3D
There are two functions provided in this library:

```cpp
void open3d_ros::open3dToRos(const open3d::geometry::PointCloud& pointcloud, sensor_msgs::PointCloud2& ros_pc2, std::string frame_id = "open3d_pointcloud");
void open3d_conversions::open3dToRos(const open3d::geometry::PointCloud & pointcloud, sensor_msgs::msg::PointCloud2 & ros_pc2, std::string frame_id = "open3d_pointcloud");

void open3d_ros::rosToOpen3d(const sensor_msgs::PointCloud2ConstPtr& ros_pc2, open3d::geometry::PointCloud& o3d_pc, bool skip_colors=false);
void open3d_conversions::rosToOpen3d(const sensor_msgs::msg::PointCloud2::SharedPtr & ros_pc2, open3d::geometry::PointCloud & o3d_pc, bool skip_colors=false);
```
* As Open3D pointclouds only contain `points`, `colors` and `normals`, the interface currently supports XYZ, XYZRGB pointclouds. XYZI pointclouds are handled by placing the `intensity` value in the `colors_`.
Expand Down
54 changes: 0 additions & 54 deletions open3d_conversions/include/open3d_conversions/open3d_conversions.h

This file was deleted.

Original file line number Diff line number Diff line change
@@ -0,0 +1,61 @@
// Copyright 2020 Autonomous Robots Lab, University of Nevada, Reno

// 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.
#ifndef OPEN3D_CONVERSIONS__OPEN3D_CONVERSIONS_HPP_
#define OPEN3D_CONVERSIONS__OPEN3D_CONVERSIONS_HPP_

// ROS2
#include <sensor_msgs/msg/point_cloud2.hpp>
#include <sensor_msgs/point_cloud2_iterator.hpp>

// Open3D
#include <open3d/Open3D.h>

// Eigen
#include <Eigen/Dense>

// C++
#include <string>

#include "open3d_conversions/visibility_control.h"

namespace open3d_conversions
{
/**
* @brief Copy data from a open3d::geometry::PointCloud to a
* sensor_msgs::msg::PointCloud2
*
* @param pointcloud Reference to the open3d geometry PointCloud
* @param ros_pc2 Reference to the sensor_msgs PointCloud2
* @param frame_id The string to be placed in the frame_id of the PointCloud2
*/
void open3dToRos(
const open3d::geometry::PointCloud & pointcloud,
sensor_msgs::msg::PointCloud2 & ros_pc2,
std::string frame_id = "open3d_pointcloud");
/**
* @brief Copy data from a sensor_msgs::msg::PointCloud2 to a
* open3d::geometry::PointCloud
*
* @param ros_pc2 Reference to the sensor_msgs PointCloud2
* @param o3d_pc Reference to the open3d geometry PointCloud
* @param skip_colors If true, only xyz fields will be copied
*/
void rosToOpen3d(
const sensor_msgs::msg::PointCloud2::SharedPtr & ros_pc2,
open3d::geometry::PointCloud & o3d_pc,
bool skip_colors = false);

} // namespace open3d_conversions

#endif // OPEN3D_CONVERSIONS__OPEN3D_CONVERSIONS_HPP_
48 changes: 48 additions & 0 deletions open3d_conversions/include/open3d_conversions/visibility_control.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,48 @@
// Copyright 2020 Autonomous Robots Lab, University of Nevada, Reno

// 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.
#ifndef OPEN3D_CONVERSIONS__VISIBILITY_CONTROL_H_
#define OPEN3D_CONVERSIONS__VISIBILITY_CONTROL_H_

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
// https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
#ifdef __GNUC__
#define OPEN3D_CONVERSIONS_EXPORT __attribute__ ((dllexport))
#define OPEN3D_CONVERSIONS_IMPORT __attribute__ ((dllimport))
#else
#define OPEN3D_CONVERSIONS_EXPORT __declspec(dllexport)
#define OPEN3D_CONVERSIONS_IMPORT __declspec(dllimport)
#endif
#ifdef OPEN3D_CONVERSIONS_BUILDING_LIBRARY
#define OPEN3D_CONVERSIONS_PUBLIC OPEN3D_CONVERSIONS_EXPORT
#else
#define OPEN3D_CONVERSIONS_PUBLIC OPEN3D_CONVERSIONS_IMPORT
#endif
#define OPEN3D_CONVERSIONS_PUBLIC_TYPE OPEN3D_CONVERSIONS_PUBLIC
#define OPEN3D_CONVERSIONS_LOCAL
#else
#define OPEN3D_CONVERSIONS_EXPORT __attribute__ ((visibility("default")))
#define OPEN3D_CONVERSIONS_IMPORT
#if __GNUC__ >= 4
#define OPEN3D_CONVERSIONS_PUBLIC __attribute__ ((visibility("default")))
#define OPEN3D_CONVERSIONS_LOCAL __attribute__ ((visibility("default")))
#else
#define OPEN3D_CONVERSIONS_PUBLIC
#define OPEN3D_CONVERSIONS_LOCAL
#endif
#define OPEN3D_CONVERSIONS_PUBLIC_TYPE
#endif

#endif // OPEN3D_CONVERSIONS__VISIBILITY_CONTROL_H_
13 changes: 6 additions & 7 deletions open3d_conversions/package.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,8 @@
<?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>open3d_conversions</name>
<version>0.0.2</version>
<version>0.1.0</version>
<description>Provides conversion functions to and from Open3D datatypes</description>

<maintainer email="[email protected]">Pranay Mathur</maintainer>
Expand All @@ -12,15 +13,13 @@

<author email="[email protected]">Pranay Mathur</author>
<author email="[email protected]">Nikhil Khedekar</author>
<buildtool_depend>ament_cmake_ros</buildtool_depend>

<buildtool_depend>catkin</buildtool_depend>
<depend>roscpp</depend>
<depend>rclcpp</depend>
<depend>sensor_msgs</depend>
<depend>eigen</depend>

<!-- The export tag contains other, unspecified, tags -->
<export>
<!-- Other tools can request additional information be placed here -->

<build_type>ament_cmake</build_type>
</export>
</package>
Loading

0 comments on commit f455edd

Please sign in to comment.