Skip to content

Commit

Permalink
Deprecating tf2 C Headers (#87)
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <[email protected]>
  • Loading branch information
CursedRock17 authored Dec 27, 2024
1 parent c7edb60 commit fc0fb8b
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 3 deletions.
2 changes: 1 addition & 1 deletion turtle_tf2_cpp/src/static_turtle_tf2_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,7 +16,7 @@

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2_ros/static_transform_broadcaster.h"

class StaticFramePublisher : public rclcpp::Node
Expand Down
2 changes: 1 addition & 1 deletion turtle_tf2_cpp/src/turtle_tf2_broadcaster.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,7 +19,7 @@

#include "geometry_msgs/msg/transform_stamped.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/LinearMath/Quaternion.h"
#include "tf2/LinearMath/Quaternion.hpp"
#include "tf2_ros/transform_broadcaster.h"
#include "turtlesim_msgs/msg/pose.hpp"

Expand Down
2 changes: 1 addition & 1 deletion turtle_tf2_cpp/src/turtle_tf2_listener.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@
#include "geometry_msgs/msg/transform_stamped.hpp"
#include "geometry_msgs/msg/twist.hpp"
#include "rclcpp/rclcpp.hpp"
#include "tf2/exceptions.h"
#include "tf2/exceptions.hpp"
#include "tf2_ros/transform_listener.h"
#include "tf2_ros/buffer.h"
#include "turtlesim_msgs/srv/spawn.hpp"
Expand Down

0 comments on commit fc0fb8b

Please sign in to comment.