Skip to content

Commit ccacda4

Browse files
authored
Jazzy "Backport" of #720 (#723)
Signed-off-by: CursedRock17 <[email protected]> Signed-off-by: Lucas Wendland <[email protected]>
1 parent 30708f6 commit ccacda4

File tree

76 files changed

+4893
-4386
lines changed

Some content is hidden

Large Commits have some content hidden by default. Use the searchbox below for content that may be hidden.

76 files changed

+4893
-4386
lines changed

test_tf2/test/buffer_core_test.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -44,10 +44,10 @@
4444
#include <geometry_msgs/msg/transform.hpp>
4545
#include <geometry_msgs/msg/transform_stamped.hpp>
4646
#include <rclcpp/rclcpp.hpp>
47-
#include <tf2/buffer_core.h>
48-
#include <tf2/exceptions.h>
49-
#include <tf2/LinearMath/Quaternion.h>
50-
#include <tf2/time.h>
47+
#include <tf2/buffer_core.hpp>
48+
#include <tf2/exceptions.hpp>
49+
#include <tf2/LinearMath/Quaternion.hpp>
50+
#include <tf2/time.hpp>
5151
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
5252
#include <tf2_ros/buffer_interface.h>
5353

test_tf2/test/test_convert.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -38,8 +38,8 @@
3838
#include <geometry_msgs/msg/point_stamped.hpp>
3939
#include <geometry_msgs/msg/point.hpp>
4040
#include <geometry_msgs/msg/vector3.hpp>
41-
#include <tf2/convert.h>
42-
#include <tf2/LinearMath/Quaternion.h>
41+
#include <tf2/convert.hpp>
42+
#include <tf2/LinearMath/Quaternion.hpp>
4343
#include <tf2_kdl/tf2_kdl.hpp>
4444
#include <tf2_bullet/tf2_bullet.hpp>
4545
#include <tf2_eigen/tf2_eigen.hpp>

test_tf2/test/test_message_filter.cpp

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -40,10 +40,10 @@
4040
#include <geometry_msgs/msg/point_stamped.hpp>
4141
#include <geometry_msgs/msg/transform_stamped.hpp>
4242
#include <rclcpp/rclcpp.hpp>
43-
#include <tf2/buffer_core.h>
44-
#include <tf2/LinearMath/Quaternion.h>
45-
#include <tf2/LinearMath/Vector3.h>
46-
#include <tf2/time.h>
43+
#include <tf2/buffer_core.hpp>
44+
#include <tf2/LinearMath/Quaternion.hpp>
45+
#include <tf2/LinearMath/Vector3.hpp>
46+
#include <tf2/time.hpp>
4747
#include <tf2_ros/buffer_interface.h>
4848
#include <tf2_ros/create_timer_ros.h>
4949
#include <tf2_ros/message_filter.h>

test_tf2/test/test_static_publisher.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -36,9 +36,9 @@
3636

3737
#include <geometry_msgs/msg/transform_stamped.hpp>
3838
#include <rclcpp/rclcpp.hpp>
39-
#include <tf2/buffer_core.h>
40-
#include <tf2/exceptions.h>
41-
#include <tf2/time.h>
39+
#include <tf2/buffer_core.hpp>
40+
#include <tf2/exceptions.hpp>
41+
#include <tf2/time.hpp>
4242
#include <tf2_ros/buffer.h>
4343
#include <tf2_ros/buffer_interface.h>
4444
#include <tf2_ros/static_transform_broadcaster.h>

test_tf2/test/test_tf2_bullet.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -33,7 +33,7 @@
3333
#include <tf2_ros/buffer.h>
3434
#include <rclcpp/rclcpp.hpp>
3535
#include <gtest/gtest.h>
36-
#include <tf2/convert.h>
36+
#include <tf2/convert.hpp>
3737

3838
std::unique_ptr<tf2_ros::Buffer> tf_buffer = nullptr;
3939
static const double EPS = 1e-3;

test_tf2/test/test_utils.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,8 @@
1818
#include <geometry_msgs/msg/quaternion_stamped.hpp>
1919
#include <geometry_msgs/msg/transform.hpp>
2020
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
21-
#include <tf2/LinearMath/Quaternion.h>
22-
#include <tf2/utils.h>
21+
#include <tf2/LinearMath/Quaternion.hpp>
22+
#include <tf2/utils.hpp>
2323
#include <tf2_kdl/tf2_kdl.hpp>
2424

2525
double epsilon = 1e-9;

tf2/CMakeLists.txt

Lines changed: 7 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -62,6 +62,13 @@ if(BUILD_TESTING)
6262
include/tf2/LinearMath/Scalar.h
6363
include/tf2/LinearMath/Transform.h
6464
include/tf2/LinearMath/Vector3.h
65+
include/tf2/LinearMath/Matrix3x3.hpp
66+
include/tf2/LinearMath/MinMax.hpp
67+
include/tf2/LinearMath/QuadWord.hpp
68+
include/tf2/LinearMath/Quaternion.hpp
69+
include/tf2/LinearMath/Scalar.hpp
70+
include/tf2/LinearMath/Transform.hpp
71+
include/tf2/LinearMath/Vector3.hpp
6572
)
6673

6774
ament_copyright(EXCLUDE ${_linter_excludes})

0 commit comments

Comments
 (0)