Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Porting tf2_bullet to ros2 #205

Merged
merged 13 commits into from
Mar 4, 2020
Empty file removed tf2_bullet/AMENT_IGNORE
Empty file.
32 changes: 20 additions & 12 deletions tf2_bullet/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -6,19 +6,27 @@ find_package(PkgConfig REQUIRED)
set(bullet_FOUND 0)
pkg_check_modules(bullet REQUIRED bullet)

find_package(catkin REQUIRED COMPONENTS geometry_msgs tf2)
find_package(ament_cmake REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(tf2 REQUIRED)
find_package(tf2_ros REQUIRED)

include_directories(include ${bullet_INCLUDE_DIRS} ${catkin_INCLUDE_DIRS})

catkin_package(INCLUDE_DIRS include ${bullet_INCLUDE_DIRS})
include_directories(include ${bullet_INCLUDE_DIRS})

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


if(CATKIN_ENABLE_TESTING)

catkin_add_gtest(test_bullet test/test_tf2_bullet.cpp)
target_link_libraries(test_bullet ${catkin_LIBRARIES} ${GTEST_LIBRARIES})

DESTINATION include/${PROJECT_NAME}
)

if(BUILD_TESTING)
find_package(ament_cmake_gtest REQUIRED)
ament_add_gtest(test_bullet test/test_tf2_bullet.cpp)
ament_target_dependencies(test_bullet
tf2
geometry_msgs
tf2_ros
)
endif()

ament_export_include_directories(include)
ament_export_libraries(${PROJECT_NAME})
ament_package()
24 changes: 12 additions & 12 deletions tf2_bullet/include/tf2_bullet/tf2_bullet.h
Original file line number Diff line number Diff line change
Expand Up @@ -34,8 +34,8 @@

#include <tf2/convert.h>
#include <LinearMath/btTransform.h>
#include <geometry_msgs/PointStamped.h>

#include <geometry_msgs/msg/point_stamped.hpp>
#include <tf2_ros/buffer_interface.h>

namespace tf2
{
Expand All @@ -44,7 +44,7 @@ namespace tf2
* \return The transform message converted to a Bullet btTransform.
*/
inline
btTransform transformToBullet(const geometry_msgs::TransformStamped& t)
btTransform transformToBullet(const geometry_msgs::msg::TransformStamped& t)
{
return btTransform(btQuaternion(t.transform.rotation.x, t.transform.rotation.y,
t.transform.rotation.z, t.transform.rotation.w),
Expand All @@ -60,9 +60,9 @@ btTransform transformToBullet(const geometry_msgs::TransformStamped& t)
*/
template <>
inline
void doTransform(const tf2::Stamped<btVector3>& t_in, tf2::Stamped<btVector3>& t_out, const geometry_msgs::TransformStamped& transform)
void doTransform(const tf2::Stamped<btVector3>& t_in, tf2::Stamped<btVector3>& t_out, const geometry_msgs::msg::TransformStamped& transform)
{
t_out = tf2::Stamped<btVector3>(transformToBullet(transform) * t_in, transform.header.stamp, transform.header.frame_id);
t_out = tf2::Stamped<btVector3>(transformToBullet(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
}

/** \brief Convert a stamped Bullet Vector3 type to a PointStamped message.
Expand All @@ -71,10 +71,10 @@ inline
* \return The vector converted to a PointStamped message.
*/
inline
geometry_msgs::PointStamped toMsg(const tf2::Stamped<btVector3>& in)
geometry_msgs::msg::PointStamped toMsg(const tf2::Stamped<btVector3>& in)
{
geometry_msgs::PointStamped msg;
msg.header.stamp = in.stamp_;
geometry_msgs::msg::PointStamped msg;
msg.header.stamp = tf2_ros::toMsg(in.stamp_);
msg.header.frame_id = in.frame_id_;
msg.point.x = in[0];
msg.point.y = in[1];
Expand All @@ -88,9 +88,9 @@ geometry_msgs::PointStamped toMsg(const tf2::Stamped<btVector3>& in)
* \param out The point converted to a timestamped Bullet Vector3.
*/
inline
void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<btVector3>& out)
void fromMsg(const geometry_msgs::msg::PointStamped& msg, tf2::Stamped<btVector3>& out)
{
out.stamp_ = msg.header.stamp;
out.stamp_ = tf2_ros::fromMsg(msg.header.stamp);
out.frame_id_ = msg.header.frame_id;
out[0] = msg.point.x;
out[1] = msg.point.y;
Expand All @@ -106,9 +106,9 @@ void fromMsg(const geometry_msgs::PointStamped& msg, tf2::Stamped<btVector3>& ou
*/
template <>
inline
void doTransform(const tf2::Stamped<btTransform>& t_in, tf2::Stamped<btTransform>& t_out, const geometry_msgs::TransformStamped& transform)
void doTransform(const tf2::Stamped<btTransform>& t_in, tf2::Stamped<btTransform>& t_out, const geometry_msgs::msg::TransformStamped& transform)
{
t_out = tf2::Stamped<btTransform>(transformToBullet(transform) * t_in, transform.header.stamp, transform.header.frame_id);
t_out = tf2::Stamped<btTransform>(transformToBullet(transform) * t_in, tf2_ros::fromMsg(transform.header.stamp), transform.header.frame_id);
}


Expand Down
2 changes: 1 addition & 1 deletion tf2_bullet/test/test_tf2_bullet.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@


#include <tf2_bullet/tf2_bullet.h>
#include <ros/ros.h>
#include <rclcpp/rclcpp.hpp>
#include <gtest/gtest.h>
#include <tf2/convert.h>

Expand Down