SMACC2
|
#include <cp_pose.hpp>
Public Member Functions | |
Pose (std::string poseFrameName="base_link", std::string referenceFrame="odom") | |
Pose (StandardReferenceFrames referenceFrame) | |
void | onInitialize () override |
void | update () override |
void | waitTransformUpdate (rclcpp::Rate r=rclcpp::Rate(20)) |
geometry_msgs::msg::Pose | toPoseMsg () |
geometry_msgs::msg::PoseStamped | toPoseStampedMsg () |
float | getYaw () |
float | getX () |
float | getY () |
float | getZ () |
const std::string & | getReferenceFrame () const |
const std::string & | getFrameId () const |
Public Member Functions inherited from smacc2::ISmaccComponent | |
ISmaccComponent () | |
virtual | ~ISmaccComponent () |
virtual std::string | getName () const |
Public Member Functions inherited from smacc2::ISmaccUpdatable | |
ISmaccUpdatable () | |
ISmaccUpdatable (rclcpp::Duration duration) | |
void | executeUpdate (rclcpp::Node::SharedPtr node) |
void | setUpdatePeriod (rclcpp::Duration duration) |
Public Attributes | |
bool | isInitialized |
Private Attributes | |
geometry_msgs::msg::PoseStamped | pose_ |
std::string | poseFrameName_ |
std::string | referenceFrame_ |
std::mutex | m_mutex_ |
Static Private Attributes | |
static std::shared_ptr< tf2_ros::Buffer > | tfBuffer_ |
static std::shared_ptr< tf2_ros::TransformListener > | tfListener_ |
static std::mutex | listenerMutex_ |
Definition at line 43 of file cp_pose.hpp.
cl_nitrosz::Pose::Pose | ( | std::string | poseFrameName = "base_link" , |
std::string | referenceFrame = "odom" |
||
) |
cl_nitrosz::Pose::Pose | ( | StandardReferenceFrames | referenceFrame | ) |
Definition at line 55 of file cp_pose.cpp.
|
inline |
|
inline |
Definition at line 76 of file cp_pose.hpp.
References referenceFrame_.
Referenced by cl_nitrosz::CbNavigateGlobalPosition::execute(), cl_nitrosz::CbAbsoluteRotate::onEntry(), cl_nitrosz::CbNavigateBackwards::onEntry(), cl_nitrosz::CbNavigateForward::onEntry(), and cl_nitrosz::CbRotate::onEntry().
float cl_nitrosz::Pose::getX | ( | ) |
float cl_nitrosz::Pose::getY | ( | ) |
float cl_nitrosz::Pose::getYaw | ( | ) |
float cl_nitrosz::Pose::getZ | ( | ) |
|
overridevirtual |
Reimplemented from smacc2::ISmaccComponent.
Definition at line 60 of file cp_pose.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), listenerMutex_, poseFrameName_, referenceFrame_, tfBuffer_, and tfListener_.
|
inline |
Definition at line 57 of file cp_pose.hpp.
References m_mutex_, and pose_.
Referenced by cl_nitrosz::CbRotateLookAt::onEntry(), cl_nitrosz::CbStopNavigation::onEntry(), and cl_nitrosz::CpWaypointNavigator::sendNextGoal().
|
inline |
|
overridevirtual |
Implements smacc2::ISmaccUpdatable.
Definition at line 124 of file cp_pose.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), isInitialized, listenerMutex_, m_mutex_, pose_, poseFrameName_, referenceFrame_, and tfBuffer_.
void cl_nitrosz::Pose::waitTransformUpdate | ( | rclcpp::Rate | r = rclcpp::Rate(20) | ) |
Definition at line 77 of file cp_pose.cpp.
References smacc2::ISmaccComponent::getLogger(), smacc2::ISmaccComponent::getNode(), isInitialized, listenerMutex_, m_mutex_, pose_, poseFrameName_, referenceFrame_, and tfBuffer_.
Referenced by cl_nitrosz::CbRotateLookAt::onEntry(), and cl_nitrosz::CbWaitPose::onEntry().
bool cl_nitrosz::Pose::isInitialized |
Definition at line 80 of file cp_pose.hpp.
Referenced by update(), and waitTransformUpdate().
|
staticprivate |
Definition at line 88 of file cp_pose.hpp.
Referenced by onInitialize(), update(), and waitTransformUpdate().
|
private |
Definition at line 93 of file cp_pose.hpp.
Referenced by toPoseMsg(), toPoseStampedMsg(), update(), and waitTransformUpdate().
|
private |
Definition at line 83 of file cp_pose.hpp.
Referenced by getX(), getY(), getYaw(), getZ(), Pose(), toPoseMsg(), toPoseStampedMsg(), update(), and waitTransformUpdate().
|
private |
Definition at line 90 of file cp_pose.hpp.
Referenced by getFrameId(), onInitialize(), update(), and waitTransformUpdate().
|
private |
Definition at line 91 of file cp_pose.hpp.
Referenced by getReferenceFrame(), onInitialize(), Pose(), update(), and waitTransformUpdate().
|
staticprivate |
Definition at line 85 of file cp_pose.hpp.
Referenced by onInitialize(), update(), and waitTransformUpdate().
|
staticprivate |
Definition at line 86 of file cp_pose.hpp.
Referenced by onInitialize().