-
Notifications
You must be signed in to change notification settings - Fork 205
Commit
This commit does not belong to any branch on this repository, and may belong to a fork outside of the repository.
Port tf2_geometry_msgs to ROS 2 (#7)
* Add python_orocos_kdl dependency for ros-*-base installs * Switch tf2_geometry_msgs to use package.xml format 2 (#217) * Switch tf2_geometry_msgs to use package.xml format 2 * Reinstate min catkin version * port tf2_geometry_msgs to ros2 * Use new tf2 <-> builtin_interfaces conversions * geometry_msgs::Quaternion -> geometry_msgs::msg::Quaternion * Workaround for orocos_kdl package shouldn't be necessary anymore We have a ros2-specific package now that has absolute paths: ros2/orocos_kinematics_dynamics@efa9674 * Revert find-and-replace changes to test file This still won't work for now but it is closer
- Loading branch information
Showing
7 changed files
with
117 additions
and
111 deletions.
There are no files selected for viewing
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Empty file.
This file contains bidirectional Unicode text that may be interpreted or compiled differently than what appears below. To review, open the file in an editor that reveals hidden Unicode characters.
Learn more about bidirectional Unicode characters
Original file line number | Diff line number | Diff line change |
---|---|---|
@@ -1,47 +1,50 @@ | ||
cmake_minimum_required(VERSION 3.5) | ||
project(tf2_geometry_msgs) | ||
|
||
find_package(orocos_kdl) | ||
find_package(catkin REQUIRED COMPONENTS geometry_msgs tf2_ros tf2) | ||
find_package(Boost COMPONENTS thread REQUIRED) | ||
|
||
# Issue #53 | ||
find_library(KDL_LIBRARY REQUIRED NAMES orocos-kdl HINTS ${orocos_kdl_LIBRARY_DIRS}) | ||
|
||
catkin_package( | ||
LIBRARIES ${KDL_LIBRARY} | ||
INCLUDE_DIRS include | ||
DEPENDS orocos_kdl | ||
CATKIN_DEPENDS geometry_msgs tf2_ros tf2) | ||
if(NOT WIN32) | ||
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++14 -Wall -Wextra") | ||
endif() | ||
|
||
find_package(orocos_kdl) | ||
find_package(ament_cmake REQUIRED) | ||
find_package(geometry_msgs REQUIRED) | ||
find_package(tf2 REQUIRED) | ||
find_package(tf2_ros REQUIRED) | ||
|
||
include_directories(include | ||
${catkin_INCLUDE_DIRS} | ||
${orocos_kdl_INCLUDE_DIRS} | ||
${tf2_INCLUDE_DIRS} | ||
${tf2_ros_INCLUDE_DIRS} | ||
${geometry_msgs_INCLUDE_DIRS} | ||
) | ||
|
||
link_directories(${orocos_kdl_LIBRARY_DIRS}) | ||
|
||
|
||
|
||
install(DIRECTORY include/${PROJECT_NAME}/ | ||
DESTINATION ${CATKIN_PACKAGE_INCLUDE_DESTINATION} | ||
DESTINATION include/${PROJECT_NAME} | ||
) | ||
|
||
catkin_python_setup() | ||
|
||
if(CATKIN_ENABLE_TESTING) | ||
|
||
find_package(catkin REQUIRED COMPONENTS geometry_msgs rostest tf2_ros tf2) | ||
|
||
add_executable(test_geometry_msgs EXCLUDE_FROM_ALL test/test_tf2_geometry_msgs.cpp) | ||
target_link_libraries(test_geometry_msgs ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ${orocos_kdl_LIBRARIES}) | ||
add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test.launch) | ||
add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test_python.launch) | ||
|
||
|
||
if(TARGET tests) | ||
add_dependencies(tests test_geometry_msgs) | ||
endif() | ||
|
||
|
||
endif() | ||
# TODO(dhood): enable python support once ported to ROS 2 | ||
# catkin_python_setup() | ||
|
||
# TODO(dhood): enable tests once ported to ROS 2 | ||
# if(CATKIN_ENABLE_TESTING) | ||
# | ||
# find_package(catkin REQUIRED COMPONENTS geometry_msgs rostest tf2_ros tf2) | ||
# | ||
# add_executable(test_geometry_msgs EXCLUDE_FROM_ALL test/test_tf2_geometry_msgs.cpp) | ||
# target_link_libraries(test_geometry_msgs ${catkin_LIBRARIES} ${GTEST_LIBRARIES} ${orocos_kdl_LIBRARIES}) | ||
# add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test.launch) | ||
# add_rostest(${CMAKE_CURRENT_SOURCE_DIR}/test/test_python.launch) | ||
# | ||
# | ||
# if(TARGET tests) | ||
# add_dependencies(tests test_geometry_msgs) | ||
# endif() | ||
# | ||
# | ||
# endif() | ||
ament_export_include_directories(include) | ||
ament_package() |
Oops, something went wrong.