File tree Expand file tree Collapse file tree 3 files changed +6
-3
lines changed Expand file tree Collapse file tree 3 files changed +6
-3
lines changed Original file line number Diff line number Diff line change @@ -25,12 +25,13 @@ find_package(Eigen3 REQUIRED)
2525ament_export_dependencies(eigen3_cmake_module)
2626ament_export_dependencies(Eigen3)
2727ament_export_dependencies(tf2)
28+ ament_export_dependencies(tf2_ros)
2829
2930if (BUILD_TESTING)
3031 find_package (ament_cmake_gtest REQUIRED)
31- find_package (ament_cmake_pytest REQUIRED)
3232
3333 # TODO(ros2/orocos_kinematics_dynamics): reenable when PyKDL is ready to use
34+ #find_package(ament_cmake_pytest REQUIRED)
3435 #ament_add_pytest_test(test_tf2_sensor_msgs_py test/test_tf2_sensor_msgs.py)
3536
3637 ament_add_gtest(test_tf2_sensor_msgs_cpp test /test_tf2_sensor_msgs.cpp)
Original file line number Diff line number Diff line change 2525 <depend >tf2_ros</depend >
2626 <!-- <depend>python_orocos_kdl</depend> -->
2727 <!-- <test_depend>rostest</test_depend> -->
28-
29- <exec_depend >tf2_ros_py</exec_depend >
28+ <!-- <exec_depend>tf2_ros_py</exec_depend> -->
3029
3130 <test_depend >ament_cmake_gtest</test_depend >
31+ <test_depend >rclcpp</test_depend >
3232
3333 <export >
3434 <build_type >ament_cmake</build_type >
Original file line number Diff line number Diff line change 2727 * POSSIBILITY OF SUCH DAMAGE.
2828 */
2929
30+ #include < memory>
3031
3132#include < builtin_interfaces/msg/time.hpp>
3233#include < geometry_msgs/msg/pose_stamped.hpp>
3334#include < gtest/gtest.h>
35+ #include < rclcpp/rclcpp.hpp>
3436#include < sensor_msgs/point_cloud2_iterator.hpp>
3537#include < tf2_ros/buffer.h>
3638#include < tf2_ros/transform_listener.h>
You can’t perform that action at this time.
0 commit comments