SMACC2
cp_pose.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 *-2020
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20#pragma once
21
22#include <mutex>
23
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>
27
28#include <tf2/transform_datatypes.h>
29#include <tf2/utils.h>
30#include <tf2_ros/buffer.h>
31#include <tf2_ros/transform_listener.h>
32
33#include <smacc2/component.hpp>
35
36namespace cl_nav2z
37{
39{
40 Map,
42};
43
45{
46public:
47 Pose(std::string poseFrameName = "base_link", std::string referenceFrame = "odom");
48
49 Pose(StandardReferenceFrames referenceFrame);
50
51 void onInitialize() override;
52
53 void update() override;
54
55 // synchronously waits a transform in the current thread
56 void waitTransformUpdate(rclcpp::Rate r = rclcpp::Rate(20));
57
58 inline geometry_msgs::msg::Pose toPoseMsg()
59 {
60 std::lock_guard<std::mutex> guard(m_mutex_);
61 return this->pose_.pose;
62 }
63
64 inline geometry_msgs::msg::PoseStamped toPoseStampedMsg()
65 {
66 std::lock_guard<std::mutex> guard(m_mutex_);
67 return this->pose_;
68 }
69
70 // get yaw in radians
71 float getYaw();
72
73 float getX();
74 float getY();
75 float getZ();
76
77 inline const std::string & getReferenceFrame() const { return referenceFrame_; }
78
79 inline const std::string & getFrameId() const { return poseFrameName_; }
80
82
83private:
84 geometry_msgs::msg::PoseStamped pose_;
85
86 static std::shared_ptr<tf2_ros::Buffer> tfBuffer_;
87 static std::shared_ptr<tf2_ros::TransformListener> tfListener_;
88
89 static std::mutex listenerMutex_;
90
91 std::string poseFrameName_;
92 std::string referenceFrame_;
93
94 std::mutex m_mutex_;
95};
96} // namespace cl_nav2z
float getX()
Definition: cp_pose.cpp:120
static std::mutex listenerMutex_
Definition: cp_pose.hpp:89
static std::shared_ptr< tf2_ros::Buffer > tfBuffer_
Definition: cp_pose.hpp:86
void update() override
Definition: cp_pose.cpp:124
static std::shared_ptr< tf2_ros::TransformListener > tfListener_
Definition: cp_pose.hpp:87
float getY()
Definition: cp_pose.cpp:121
std::mutex m_mutex_
Definition: cp_pose.hpp:94
const std::string & getFrameId() const
Definition: cp_pose.hpp:79
float getYaw()
Definition: cp_pose.cpp:118
geometry_msgs::msg::PoseStamped toPoseStampedMsg()
Definition: cp_pose.hpp:64
const std::string & getReferenceFrame() const
Definition: cp_pose.hpp:77
Pose(std::string poseFrameName="base_link", std::string referenceFrame="odom")
Definition: cp_pose.cpp:35
void onInitialize() override
Definition: cp_pose.cpp:60
bool isInitialized
Definition: cp_pose.hpp:81
std::string referenceFrame_
Definition: cp_pose.hpp:92
geometry_msgs::msg::Pose toPoseMsg()
Definition: cp_pose.hpp:58
void waitTransformUpdate(rclcpp::Rate r=rclcpp::Rate(20))
Definition: cp_pose.cpp:77
geometry_msgs::msg::PoseStamped pose_
Definition: cp_pose.hpp:84
float getZ()
Definition: cp_pose.cpp:122
std::string poseFrameName_
Definition: cp_pose.hpp:91
StandardReferenceFrames
Definition: cp_pose.hpp:39