Skip to content

Commit

Permalink
merging 04cf29d to fix #7
Browse files Browse the repository at this point in the history
  • Loading branch information
tfoote committed Jun 25, 2013
1 parent 37aca97 commit e0aae10
Show file tree
Hide file tree
Showing 21 changed files with 3,752 additions and 0 deletions.
2 changes: 2 additions & 0 deletions geometry_experimental/package.xml
Expand Up @@ -15,7 +15,9 @@

<buildtool_depend>catkin</buildtool_depend>

<run_depend>test_tf2</run_depend>
<run_depend>tf2</run_depend>
<run_depend>tf2_bullet</run_depend>
<run_depend>tf2_geometry_msgs</run_depend>
<run_depend>tf2_kdl</run_depend>
<run_depend>tf2_msgs</run_depend>
Expand Down
27 changes: 27 additions & 0 deletions test_tf2/CMakeLists.txt
@@ -0,0 +1,27 @@
cmake_minimum_required(VERSION 2.8.3)
project(test_tf2)

find_package(catkin REQUIRED COMPONENTS rostest tf tf2 tf2_bullet tf2_ros tf2_geometry_msgs tf2_kdl tf2_msgs roscpp)
find_package(Boost REQUIRED COMPONENTS thread)

catkin_package()

catkin_add_gtest(buffer_core_test test/buffer_core_test.cpp)
catkin_add_gtest(test_message_filter test/test_message_filter.cpp)
catkin_add_gtest(test_convert test/test_convert.cppp)

add_executable(test_buffer_server test/test_buffer_server.cpp)
target_link_libraries(test_buffer_server ${Boost_LIBRARIES})

add_executable(test_buffer_client test/test_buffer_client.cpp)
#!!! rosbuild_add_gtest_build_flags(test_buffer_client)

catkin_add_gtest(test/buffer_client_tester.launch)

add_executable(test_static_publisher test/test_static_publisher.cpp)
#!!! rosbuild_add_gtest_build_flags(test_static_publisher)

catkin_add_gtest(test/static_publisher.launch)



1 change: 1 addition & 0 deletions test_tf2/Makefile
@@ -0,0 +1 @@
include $(shell rospack find mk)/cmake.mk
26 changes: 26 additions & 0 deletions test_tf2/mainpage.dox
@@ -0,0 +1,26 @@
/**
\mainpage
\htmlinclude manifest.html

\b test_tf2 is ...

<!--
Provide an overview of your package.
-->


\section codeapi Code API

<!--
Provide links to specific auto-generated API documentation within your
package that is of particular interest to a reader. Doxygen will
document pretty much every part of your code, so do your best here to
point the reader to the actual API.

If your codebase is fairly large or has different sets of APIs, you
should use the doxygen 'group' tag to keep these APIs together. For
example, the roscpp documentation has 'libros' group.
-->


*/
39 changes: 39 additions & 0 deletions test_tf2/package-backup.xml
@@ -0,0 +1,39 @@
<package>
<name>test_tf2</name>
<version>0.2.4</version>
<description>
tf2 unit tests
</description>
<author>Tully Foote</author>
<author>Eitan Marder-Eppstein</author>
<maintainer email="tfoote@willowgarage.com">Tully Foote</maintainer>
<license>BSD</license>
<license>LGPL</license>

<url type="website">http://www.ros.org/wiki/geometry_experimental</url>

<buildtool_depend>catkin</buildtool_depend>

<build_depend>rostest</build_depend>
<build_depend>tf</build_depend>
<build_depend>tf2</build_depend>
<build_depend>tf2_bullet</build_depend>
<build_depend>tf2_ros</build_depend>
<build_depend>tf2_geometry_msgs</build_depend>
<build_depend>tf2_kdl</build_depend>
<build_depend>tf2_msgs</build_depend>
<build_depend>roscpp</build_depend>

<run_depend>rostest</run_depend>
<run_depend>tf</run_depend>
<run_depend>tf2</run_depend>
<run_depend>tf2_bullet</run_depend>
<run_depend>tf2_ros</run_depend>
<run_depend>tf2_geometry_msgs</run_depend>
<run_depend>tf2_kdl</run_depend>
<run_depend>tf2_msgs</run_depend>
<run_depend>roscpp</run_depend>

</package>


5 changes: 5 additions & 0 deletions test_tf2/test/buffer_client_tester.launch
@@ -0,0 +1,5 @@
<launch>
<node pkg="tf" type="static_transform_publisher" name="test_static_pub" args="5 6 7 0 0 0 a b 100" />
<node name="test_buffer_server" pkg="test_tf2" type="test_buffer_server" output="screen" />
<test test-name="test_buffer_client_test" pkg="test_tf2" type="test_buffer_client" args="--text" />
</launch>

0 comments on commit e0aae10

Please sign in to comment.