Skip to content

Commit

Permalink
Revert "Removing LinearMath C++ Header"
Browse files Browse the repository at this point in the history
This reverts commit 62879df.
  • Loading branch information
CursedRock17 committed Nov 5, 2024
1 parent 62879df commit 177de4d
Show file tree
Hide file tree
Showing 30 changed files with 2,970 additions and 2,802 deletions.
2 changes: 1 addition & 1 deletion test_tf2/test/buffer_core_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@
#include <rclcpp/rclcpp.hpp>
#include <tf2/buffer_core.hpp>
#include <tf2/exceptions.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>
#include <tf2/time.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2_ros/buffer_interface.h>
Expand Down
2 changes: 1 addition & 1 deletion test_tf2/test/test_convert.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@
#include <geometry_msgs/msg/point.hpp>
#include <geometry_msgs/msg/vector3.hpp>
#include <tf2/convert.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>
#include <tf2_kdl/tf2_kdl.hpp>
#include <tf2_bullet/tf2_bullet.hpp>
#include <tf2_eigen/tf2_eigen.hpp>
Expand Down
4 changes: 2 additions & 2 deletions test_tf2/test/test_message_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -41,8 +41,8 @@
#include <geometry_msgs/msg/transform_stamped.hpp>
#include <rclcpp/rclcpp.hpp>
#include <tf2/buffer_core.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Vector3.h>
#include <tf2/LinearMath/Quaternion.hpp>
#include <tf2/LinearMath/Vector3.hpp>
#include <tf2/time.hpp>
#include <tf2_ros/buffer_interface.h>
#include <tf2_ros/create_timer_ros.h>
Expand Down
2 changes: 1 addition & 1 deletion test_tf2/test/test_utils.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -18,7 +18,7 @@
#include <geometry_msgs/msg/quaternion_stamped.hpp>
#include <geometry_msgs/msg/transform.hpp>
#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
#include <tf2/LinearMath/Quaternion.h>
#include <tf2/LinearMath/Quaternion.hpp>
#include <tf2/utils.hpp>
#include <tf2_kdl/tf2_kdl.hpp>

Expand Down
7 changes: 7 additions & 0 deletions tf2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -62,6 +62,13 @@ if(BUILD_TESTING)
include/tf2/LinearMath/Scalar.h
include/tf2/LinearMath/Transform.h
include/tf2/LinearMath/Vector3.h
include/tf2/LinearMath/Matrix3x3.hpp
include/tf2/LinearMath/MinMax.hpp
include/tf2/LinearMath/QuadWord.hpp
include/tf2/LinearMath/Quaternion.hpp
include/tf2/LinearMath/Scalar.hpp
include/tf2/LinearMath/Transform.hpp
include/tf2/LinearMath/Vector3.hpp
)

ament_copyright(EXCLUDE ${_linter_excludes})
Expand Down
Loading

0 comments on commit 177de4d

Please sign in to comment.