diff --git a/mg_odometry/src/mg_odom_publisher.cpp b/mg_odometry/src/mg_odom_publisher.cpp index a811740..e6504e3 100644 --- a/mg_odometry/src/mg_odom_publisher.cpp +++ b/mg_odometry/src/mg_odom_publisher.cpp @@ -5,7 +5,7 @@ #include #include "geometry_msgs/msg/transform_stamped.hpp" -#include "tf2_ros/static_transform_broadcaster.h" +#include "tf2_ros/transform_broadcaster.h" #include "tf2_geometry_msgs/tf2_geometry_msgs.hpp" #include "tf2/LinearMath/Transform.hpp" @@ -25,16 +25,16 @@ class MgOdomPublisher : public rclcpp::Node { this->declare_parameter("target", "base-link"); this->declare_parameter("serial_path", ENCODER_SERIAL_PATH_DEFAULT); - tf_static_broadcaster_ = std::make_shared(this); + tf_broadcaster_ = std::make_shared(this); timer_ = this->create_wall_timer(std::chrono::milliseconds(TIMEOUT), std::bind(&MgOdomPublisher::timer_callback, this)); } private: - std::shared_ptr tf_static_broadcaster_; - rclcpp::TimerBase::SharedPtr timer_; - LibSerial::SerialStream enc_serial_port_; + std::shared_ptr tf_broadcaster_; + rclcpp::TimerBase::SharedPtr timer_; + LibSerial::SerialStream enc_serial_port_; void timer_callback() { double _x = NAN; @@ -73,7 +73,7 @@ class MgOdomPublisher : public rclcpp::Node { const tf2::Transform tf(tf2::Transform(q, tf2::Vector3(x, y, 0))); tf2::convert(tf, t.transform); - tf_static_broadcaster_->sendTransform(t); + tf_broadcaster_->sendTransform(t); } };