28using namespace std::chrono_literals;
35Pose::Pose(std::string targetFrame, std::string referenceFrame)
36: isInitialized(false), poseFrameName_(targetFrame), referenceFrame_(referenceFrame)
44 switch (referenceFrame)
63 getLogger(),
"[Pose] Creating Pose tracker component to track %s in the reference frame %s",
80 RCLCPP_INFO(
getLogger(),
"[Pose Component] waitTransformUpdate");
81 while (rclcpp::ok() && !found)
83 tf2::Stamped<tf2::Transform> transform;
92 auto transformstamped =
94 tf2::fromMsg(transformstamped, transform);
98 std::lock_guard<std::mutex> guard(
m_mutex_);
99 tf2::toMsg(transform, this->
pose_.pose);
100 this->
pose_.header.stamp = tf2_ros::toRclcpp(transform.stamp_);
105 catch (tf2::TransformException & ex)
107 RCLCPP_ERROR_STREAM_THROTTLE(
110 <<
"] ) is failing on pose update : " << ex.what());
115 RCLCPP_INFO(
getLogger(),
"[Pose Component] waitTransformUpdate -> pose found!");
126 tf2::Stamped<tf2::Transform> transform;
131 RCLCPP_DEBUG(
getLogger(),
"[pose] looking up transform");
132 auto transformstamped =
134 tf2::fromMsg(transformstamped, transform);
138 std::lock_guard<std::mutex> guard(
m_mutex_);
139 tf2::toMsg(transform, this->
pose_.pose);
140 this->
pose_.header.stamp = tf2_ros::toRclcpp(transform.stamp_);
144 catch (tf2::TransformException & ex)
147 RCLCPP_ERROR_STREAM_THROTTLE(
150 <<
"] ) is failing on pose update : " << ex.what());
static std::mutex listenerMutex_
static std::shared_ptr< tf2_ros::Buffer > tfBuffer_
static std::shared_ptr< tf2_ros::TransformListener > tfListener_
Pose(std::string poseFrameName="base_link", std::string referenceFrame="odom")
void onInitialize() override
std::string referenceFrame_
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
geometry_msgs::msg::PoseStamped pose_
std::string poseFrameName_
rclcpp::Logger getLogger()
rclcpp::Node::SharedPtr getNode()
std::string referenceFrameToString(StandardReferenceFrames referenceFrame)