SMACC2
Loading...
Searching...
No Matches
cp_tf_listener.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 *****************************************************************************************************************/
20
21#pragma once
22
23#include <smacc2/component.h>
24#include <smacc2/smacc_updatable.h>
25
26#include <tf2/transform_datatypes.h>
27#include <tf2/transform_listener.h>
28#include <geometry_msgs/msg/pose.hpp>
29#include <mutex>
30#include <thread>
31
33{
35{
36 std::mutex mutex_;
37 geometry_msgs::msg::PoseStamped pose_;
38 std::string targetPoseFrame_;
40 bool once = true;
41 bool isInitialized = false;
42};
43
45{
46public:
48
49 virtual void update() override
50 {
51 for (auto & poseTrack : poseTracks_)
52 {
53 tf2::Stamped<tf2::Transform> transform;
54 try
55 {
56 {
57 std::lock_guard<std::mutex> lock(listenerMutex_);
58 tfListener_->lookupTransform(
59 poseTrack->referenceBaseFrame_, poseTrack->targetPoseFrame_, rclcpp::Time(0),
60 transform);
61 }
62
63 {
64 std::lock_guard<std::mutex> guard(m_mutex_);
65 poseTrack->pose_.pose = tf2::toMsg(transform);
66 poseTrack->pose_.header.stamp = transform.stamp_;
67 poseTrack->pose_.header.frame_id = poseTrack->referenceBaseFrame_;
68 poseTrack->isInitialized = true;
69 }
70 }
71 catch (tf2::TransformException ex)
72 {
73 RCLCPP_ERROR_STREAM_THROTTLE(
74 1, "[Component pose] (getLogger(), " << poseFrameName_ << "/[" << referenceFrame_
75 << "] ) is failing on pose update : " << ex.what());
76 }
77 }
78 }
79
81 std::string & targetPoseFrameName, std::string & referenceBaseFrame,
82 geometry_msgs::msg::Pose & out)
83 {
84 }
85
86 std::future<geometry_msgs::msg::Pose> waitForNextTransform(
87 std::string & targetName, std::string & referenceBaseFrame)
88 {
89 tracks_
90 }
91
92private:
93 static std::shared_ptr<tf2_ros::TransformListener> tfListener_;
94 static std::mutex listenerMutex_;
95
96 std::mutex m_mutex_;
97 std::list<std::shared_ptr<TfPoseTrack>> poseTracks_;
98};
99} // namespace cl_move_base_z
static std::shared_ptr< tf2_ros::TransformListener > tfListener_
virtual void update() override
std::list< std::shared_ptr< TfPoseTrack > > poseTracks_
std::future< geometry_msgs::msg::Pose > waitForNextTransform(std::string &targetName, std::string &referenceBaseFrame)
void getLastTransform(std::string &targetPoseFrameName, std::string &referenceBaseFrame, geometry_msgs::msg::Pose &out)
static std::mutex listenerMutex_
geometry_msgs::msg::PoseStamped pose_