.. _program_listing_file__tmp_ws_src_SMACC2_smacc2_client_library_nav2z_client_nav2z_client_include_nav2z_client_components_pose_cp_pose.hpp: Program Listing for File cp_pose.hpp ==================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/SMACC2/smacc2_client_library/nav2z_client/nav2z_client/include/nav2z_client/components/pose/cp_pose.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. /***************************************************************************************************************** *-2020 * Authors: Pablo Inigo Blasco, Brett Aldrich * ******************************************************************************************************************/ #pragma once #include #include #include #include #include #include #include #include #include #include namespace cl_nav2z { enum class StandardReferenceFrames { Map, Odometry }; class Pose : public smacc2::ISmaccComponent, public smacc2::ISmaccUpdatable { public: Pose(std::string poseFrameName = "base_link", std::string referenceFrame = "odom"); Pose(StandardReferenceFrames referenceFrame); void onInitialize() override; void update() override; // synchronously waits a transform in the current thread void waitTransformUpdate(rclcpp::Rate r = rclcpp::Rate(20)); inline geometry_msgs::msg::Pose toPoseMsg() { std::lock_guard guard(m_mutex_); return this->pose_.pose; } inline geometry_msgs::msg::PoseStamped toPoseStampedMsg() { std::lock_guard guard(m_mutex_); return this->pose_; } // get yaw in radians float getYaw(); float getX(); float getY(); float getZ(); inline const std::string & getReferenceFrame() const { return referenceFrame_; } inline const std::string & getFrameId() const { return poseFrameName_; } bool isInitialized; private: geometry_msgs::msg::PoseStamped pose_; static std::shared_ptr tfBuffer_; static std::shared_ptr tfListener_; static std::mutex listenerMutex_; std::string poseFrameName_; std::string referenceFrame_; std::mutex m_mutex_; }; } // namespace cl_nav2z