Skip to content

Commit

Permalink
Port tf2_geometry_msgs to ROS 2 (#7)
Browse files Browse the repository at this point in the history
* 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
dhood authored Mar 31, 2017
1 parent 678103f commit a0896de
Show file tree
Hide file tree
Showing 7 changed files with 117 additions and 111 deletions.
7 changes: 4 additions & 3 deletions tf2/include/tf2/convert.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,9 +34,6 @@

#include <builtin_interfaces/msg/time.hpp>

// TODO(tfoote)
#error This has not been converted to ROS2 and will not compile

#include <tf2/transform_datatypes.h>
#include <tf2/exceptions.h>
#include <geometry_msgs/msg/transform_stamped.hpp>
Expand Down Expand Up @@ -112,6 +109,9 @@ template<typename A, typename B>
* \param a an object to convert from
* \param b the object to convert to
*/

//TODO(dhood): re-instate if/when IsMessage message traits available in ROS 2
/*
template <class A, class B>
void convert(const A& a, B& b)
{
Expand All @@ -126,6 +126,7 @@ template <class A>
if(&a1 != &a2)
a2 = a1;
}
*/


}
Expand Down
14 changes: 7 additions & 7 deletions tf2/include/tf2/impl/utils.h
Original file line number Diff line number Diff line change
Expand Up @@ -32,22 +32,22 @@ tf2::Quaternion toQuaternion(const tf2::Quaternion& q) {
}

/** Function needed for the generalization of toQuaternion
* \param q a geometry_msgs::Quaternion
* \param q a geometry_msgs::msg::Quaternion
* \return a copy of the same quaternion as a tf2::Quaternion
*/
inline
tf2::Quaternion toQuaternion(const geometry_msgs::Quaternion& q) {
tf2::Quaternion toQuaternion(const geometry_msgs::msg::Quaternion& q) {
tf2::Quaternion res;
fromMsg(q, res);
return res;
}

/** Function needed for the generalization of toQuaternion
* \param q a geometry_msgs::QuaternionStamped
* \param q a geometry_msgs::msg::QuaternionStamped
* \return a copy of the same quaternion as a tf2::Quaternion
*/
inline
tf2::Quaternion toQuaternion(const geometry_msgs::QuaternionStamped& q) {
tf2::Quaternion toQuaternion(const geometry_msgs::msg::QuaternionStamped& q) {
tf2::Quaternion res;
fromMsg(q.quaternion, res);
return res;
Expand All @@ -59,18 +59,18 @@ tf2::Quaternion toQuaternion(const geometry_msgs::QuaternionStamped& q) {
*/
template<typename T>
tf2::Quaternion toQuaternion(const tf2::Stamped<T>& t) {
geometry_msgs::QuaternionStamped q = toMsg<tf2::Stamped<T>, geometry_msgs::QuaternionStamped>(t);
geometry_msgs::msg::QuaternionStamped q = toMsg<tf2::Stamped<T>, geometry_msgs::msg::QuaternionStamped>(t);
return toQuaternion(q);
}

/** Generic version of toQuaternion. It tries to convert the argument
* to a geometry_msgs::Quaternion
* to a geometry_msgs::msg::Quaternion
* \param t some object
* \return a copy of the same quaternion as a tf2::Quaternion
*/
template<typename T>
tf2::Quaternion toQuaternion(const T& t) {
geometry_msgs::Quaternion q = toMsg<T, geometry_msgs::QuaternionStamped>(t);
geometry_msgs::msg::Quaternion q = toMsg<T, geometry_msgs::msg::QuaternionStamped>(t);
return toQuaternion(q);
}

Expand Down
Empty file removed tf2_geometry_msgs/AMENT_IGNORE
Empty file.
67 changes: 35 additions & 32 deletions tf2_geometry_msgs/CMakeLists.txt
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()
Loading

0 comments on commit a0896de

Please sign in to comment.