Skip to content

Commit 5d6b865

Browse files
author
wep21
committed
Ros2 migration for octomap ros
Signed-off-by: wep21 <border_goldenmarket@yahoo.co.jp>
1 parent 648dccd commit 5d6b865

File tree

7 files changed

+310
-241
lines changed

7 files changed

+310
-241
lines changed

CMakeLists.txt

Lines changed: 19 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,29 +1,25 @@
1-
cmake_minimum_required(VERSION 2.8)
1+
cmake_minimum_required(VERSION 3.5)
22
project(octomap_ros)
33

4-
find_package(catkin REQUIRED COMPONENTS octomap_msgs sensor_msgs tf)
5-
find_package(OCTOMAP REQUIRED)
4+
if(NOT CMAKE_CXX_STANDARD)
5+
set(CMAKE_CXX_STANDARD 14)
6+
set(CMAKE_CXX_STANDARD_REQUIRED ON)
7+
set(CMAKE_CXX_EXTENSIONS OFF)
8+
endif()
9+
if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
10+
add_compile_options(-Wall -Wextra -Wpedantic)
11+
endif()
612

7-
catkin_package(
8-
INCLUDE_DIRS include
9-
LIBRARIES ${PROJECT_NAME}
10-
CATKIN_DEPENDS octomap_msgs sensor_msgs tf
11-
DEPENDS OCTOMAP)
13+
find_package(ament_cmake_auto REQUIRED)
14+
ament_auto_find_build_dependencies()
1215

13-
include_directories(include ${catkin_INCLUDE_DIRS})
16+
ament_auto_add_library(${PROJECT_NAME} SHARED
17+
src/conversions.cpp
18+
)
1419

15-
add_library(${PROJECT_NAME} src/conversions.cpp)
16-
add_dependencies(${PROJECT_NAME} ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS})
17-
target_link_libraries(${PROJECT_NAME} ${catkin_LIBRARIES} ${OCTOMAP_LIBRARIES})
18-
target_include_directories(${PROJECT_NAME}
19-
SYSTEM PUBLIC ${catkin_INCLUDE_DIRS} ${OCTOMAP_INCLUDE_DIRS}
20-
PUBLIC include)
20+
if(BUILD_TESTING)
21+
find_package(ament_lint_auto REQUIRED)
22+
ament_lint_auto_find_test_dependencies()
23+
endif()
2124

22-
install(TARGETS ${PROJECT_NAME}
23-
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
24-
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION})
25-
26-
install(DIRECTORY include/${PROJECT_NAME}/
27-
DESTINATION ${CATKIN_GLOBAL_INCLUDE_DESTINATION}/${PROJECT_NAME}/
28-
FILES_MATCHING PATTERN "*.h"
29-
PATTERN ".svn" EXCLUDE)
25+
ament_auto_package()

CONTRIBUTING.md

Lines changed: 18 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,18 @@
1+
Any contribution that you make to this repository will
2+
be under the 3-Clause BSD License, as dictated by that
3+
[license](https://opensource.org/licenses/BSD-3-Clause).
4+
5+
~~~
6+
1. Submission of Contributions. Unless You explicitly state otherwise,
7+
any Contribution intentionally submitted for inclusion in the Work
8+
by You to the Licensor shall be under the terms and conditions of
9+
this License, without any additional terms or conditions.
10+
Notwithstanding the above, nothing herein shall supersede or modify
11+
the terms of any separate license agreement you may have executed
12+
with Licensor regarding such Contributions.
13+
~~~
14+
15+
Contributors must sign-off each commit by adding a `Signed-off-by: ...`
16+
line to commit messages to certify that they have the right to submit
17+
the code they are contributing to the project according to the
18+
[Developer Certificate of Origin (DCO)](https://developercertificate.org/).

LICENSE

Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
BSD 3-Clause License
2+
3+
Copyright (c) 2011, A. Hornung, University of Freiburg
4+
All rights reserved.
5+
6+
Redistribution and use in source and binary forms, with or without
7+
modification, are permitted provided that the following conditions are met:
8+
9+
* Redistributions of source code must retain the above copyright notice, this
10+
list of conditions and the following disclaimer.
11+
12+
* Redistributions in binary form must reproduce the above copyright notice,
13+
this list of conditions and the following disclaimer in the documentation
14+
and/or other materials provided with the distribution.
15+
16+
* Neither the name of the copyright holder nor the names of its
17+
contributors may be used to endorse or promote products derived from
18+
this software without specific prior written permission.
19+
20+
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
21+
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
22+
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
23+
DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
24+
FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
25+
DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
26+
SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
27+
CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
28+
OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
29+
OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.

include/octomap_ros/conversions.h

Lines changed: 0 additions & 118 deletions
This file was deleted.

include/octomap_ros/conversions.hpp

Lines changed: 131 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,131 @@
1+
/**
2+
* OctoMap ROS integration
3+
*
4+
* @author A. Hornung, University of Freiburg, Copyright (C) 2011-2012.
5+
* @see http://www.ros.org/wiki/octomap_ros
6+
* License: BSD
7+
*/
8+
9+
// Copyright 2011, A. Hornung, University of Freiburg. All rights reserved.
10+
//
11+
// Redistribution and use in source and binary forms, with or without
12+
// modification, are permitted provided that the following conditions are met:
13+
//
14+
// * Redistributions of source code must retain the above copyright
15+
// notice, this list of conditions and the following disclaimer.
16+
//
17+
// * Redistributions in binary form must reproduce the above copyright
18+
// notice, this list of conditions and the following disclaimer in the
19+
// documentation and/or other materials provided with the distribution.
20+
//
21+
// * Neither the name of the Willow Garage nor the names of its
22+
// contributors may be used to endorse or promote products derived from
23+
// this software without specific prior written permission.
24+
//
25+
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
26+
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
27+
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
28+
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
29+
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
30+
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
31+
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
32+
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
33+
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
34+
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
35+
// POSSIBILITY OF SUCH DAMAGE.
36+
37+
#ifndef OCTOMAP_ROS__CONVERSIONS_HPP_
38+
#define OCTOMAP_ROS__CONVERSIONS_HPP_
39+
40+
#include <octomap/octomap.h>
41+
42+
#include <geometry_msgs/msg/point.hpp>
43+
#include <sensor_msgs/msg/point_cloud2.hpp>
44+
#include <tf2/LinearMath/Quaternion.h>
45+
#include <tf2/LinearMath/Transform.h>
46+
#include <tf2/LinearMath/Vector3.h>
47+
48+
namespace octomap
49+
{
50+
/**
51+
* @brief Conversion from octomap::point3d_list (e.g. all occupied nodes from getOccupied()) to
52+
* sensor_msgs::PointCloud2
53+
*
54+
* @param points
55+
* @param cloud
56+
*/
57+
void pointsOctomapToPointCloud2(
58+
const octomap::point3d_list & points,
59+
sensor_msgs::msg::PointCloud2 & cloud);
60+
61+
/**
62+
* @brief Conversion from a sensor_msgs::PointCLoud2
63+
* to octomap::Pointcloud, used internally in OctoMap
64+
*
65+
* @param cloud
66+
* @param octomapCloud
67+
*/
68+
void pointCloud2ToOctomap(
69+
const sensor_msgs::msg::PointCloud2 & cloud,
70+
octomap::Pointcloud & octomapCloud);
71+
72+
/// Conversion from octomap::point3d to geometry_msgs::Point
73+
static inline geometry_msgs::msg::Point pointOctomapToMsg(const octomap::point3d & octomapPt)
74+
{
75+
return geometry_msgs::build<geometry_msgs::msg::Point>()
76+
.x(octomapPt.x())
77+
.y(octomapPt.y())
78+
.z(octomapPt.z());
79+
}
80+
81+
/// Conversion from geometry_msgs::Point to octomap::point3d
82+
static inline octomap::point3d pointMsgToOctomap(const geometry_msgs::msg::Point & ptMsg)
83+
{
84+
return octomap::point3d(ptMsg.x, ptMsg.y, ptMsg.z);
85+
}
86+
87+
/// Conversion from octomap::point3d to tf2::Vector3
88+
static inline tf2::Vector3 pointOctomapToTf(const point3d & octomapPt)
89+
{
90+
return tf2::Vector3(octomapPt.x(), octomapPt.y(), octomapPt.z());
91+
}
92+
93+
/// Conversion from tf::Point to octomap::point3d
94+
static inline octomap::point3d pointTfToOctomap(const tf2::Vector3 & vTf)
95+
{
96+
return point3d(vTf.x(), vTf.y(), vTf.z());
97+
}
98+
99+
/// Conversion from octomap Quaternion to tf2::Quaternion
100+
static inline tf2::Quaternion quaternionOctomapToTf(const octomath::Quaternion & octomapQ)
101+
{
102+
return tf2::Quaternion(octomapQ.x(), octomapQ.y(), octomapQ.z(), octomapQ.u());
103+
}
104+
105+
/// Conversion from tf2::Quaternion to octomap Quaternion
106+
static inline octomath::Quaternion quaternionTfToOctomap(const tf2::Quaternion & qTf)
107+
{
108+
return octomath::Quaternion(qTf.w(), qTf.x(), qTf.y(), qTf.z());
109+
}
110+
111+
/// Conversion from octomap::pose6f to tf::Pose
112+
static inline tf2::Transform poseOctomapToTf(const octomap::pose6d & octomapPose)
113+
{
114+
return tf2::Transform(
115+
quaternionOctomapToTf(octomapPose.rot()),
116+
pointOctomapToTf(octomapPose.trans()));
117+
}
118+
119+
/// Conversion from tf::Pose to octomap::pose6d
120+
static inline octomap::pose6d poseTfToOctomap(const tf2::Transform & transformTf)
121+
{
122+
return octomap::pose6d(
123+
pointTfToOctomap(transformTf.getOrigin()),
124+
quaternionTfToOctomap(transformTf.getRotation()));
125+
}
126+
127+
128+
} // namespace octomap
129+
130+
131+
#endif // OCTOMAP_ROS__CONVERSIONS_HPP_

package.xml

Lines changed: 17 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -1,27 +1,30 @@
1-
<package>
1+
<?xml version="1.0"?>
2+
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
3+
<package format="3">
24
<name>octomap_ros</name>
35
<version>0.4.1</version>
46
<description>
57
octomap_ros provides conversion functions between ROS and OctoMap's native types.
68
This enables a convenvient use of the octomap package in ROS.
7-
89
</description>
9-
<author email="armin@hornung.io">Armin Hornung</author>
1010
<maintainer email="opensource@wolfgangmerkt.com">Wolfgang Merkt</maintainer>
1111
<maintainer email="armin@hornung.io">Armin Hornung</maintainer>
1212
<license>BSD</license>
1313
<url type="website">http://ros.org/wiki/octomap_ros</url>
1414
<url type="bugtracker">https://github.com/OctoMap/octomap_ros/issues</url>
15-
16-
<buildtool_depend>catkin</buildtool_depend>
17-
18-
<build_depend>octomap_msgs</build_depend>
19-
<build_depend>octomap</build_depend>
20-
<build_depend>sensor_msgs</build_depend>
21-
<build_depend>tf</build_depend>
15+
<author email="armin@hornung.io">Armin Hornung</author>
16+
17+
<buildtool_depend>ament_cmake_auto</buildtool_depend>
18+
19+
<depend>octomap_msgs</depend>
20+
<depend>octomap</depend>
21+
<depend>sensor_msgs</depend>
22+
<depend>tf2</depend>
23+
24+
<test_depend>ament_lint_auto</test_depend>
25+
<test_depend>ament_lint_common</test_depend>
2226

23-
<run_depend>octomap_msgs</run_depend>
24-
<run_depend>octomap</run_depend>
25-
<run_depend>sensor_msgs</run_depend>
26-
<run_depend>tf</run_depend>
27+
<export>
28+
<build_type>ament_cmake</build_type>
29+
</export>
2730
</package>

0 commit comments

Comments
 (0)