24#include <geometry_msgs/msg/pose_stamped.h>
25#include <geometry_msgs/msg/quaternion_stamped.hpp>
26#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
28#include <tf2/transform_datatypes.h>
30#include <tf2_ros/buffer.h>
31#include <tf2_ros/transform_listener.h>
47 Pose(std::string poseFrameName =
"base_link", std::string referenceFrame =
"odom");
60 std::lock_guard<std::mutex> guard(
m_mutex_);
61 return this->
pose_.pose;
66 std::lock_guard<std::mutex> guard(
m_mutex_);
84 geometry_msgs::msg::PoseStamped
pose_;
87 static std::shared_ptr<tf2_ros::TransformListener>
tfListener_;
static std::mutex listenerMutex_
static std::shared_ptr< tf2_ros::Buffer > tfBuffer_
static std::shared_ptr< tf2_ros::TransformListener > tfListener_
const std::string & getFrameId() const
geometry_msgs::msg::PoseStamped toPoseStampedMsg()
const std::string & getReferenceFrame() const
Pose(std::string poseFrameName="base_link", std::string referenceFrame="odom")
void onInitialize() override
std::string referenceFrame_
geometry_msgs::msg::Pose toPoseMsg()
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
geometry_msgs::msg::PoseStamped pose_
std::string poseFrameName_