SMACC2
|
#include <cp_tf_listener.hpp>
Public Member Functions | |
CpTFListener () | |
virtual void | update () override |
void | getLastTransform (std::string &targetPoseFrameName, std::string &referenceBaseFrame, geometry_msgs::msg::Pose &out) |
std::future< geometry_msgs::msg::Pose > | waitForNextTransform (std::string &targetName, std::string &referenceBaseFrame) |
![]() | |
ISmaccComponent () | |
virtual | ~ISmaccComponent () |
virtual std::string | getName () const |
![]() | |
ISmaccUpdatable () | |
ISmaccUpdatable (rclcpp::Duration duration) | |
void | executeUpdate (rclcpp::Node::SharedPtr node) |
void | setUpdatePeriod (rclcpp::Duration duration) |
Private Attributes | |
std::mutex | m_mutex_ |
std::list< std::shared_ptr< TfPoseTrack > > | poseTracks_ |
Static Private Attributes | |
static std::shared_ptr< tf2_ros::TransformListener > | tfListener_ |
static std::mutex | listenerMutex_ |
Additional Inherited Members | |
![]() | |
virtual void | onInitialize () |
template<typename EventType > | |
void | postEvent (const EventType &ev) |
template<typename EventType > | |
void | postEvent () |
template<typename TOrthogonal , typename TSourceObject > | |
void | onOrthogonalAllocation () |
template<typename TComponent > | |
void | requiresComponent (TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false) |
template<typename TComponent > | |
void | requiresComponent (std::string name, TComponent *&requiredComponentStorage, bool throwExceptionIfNotExist=false) |
template<typename TClient > | |
void | requiresClient (TClient *&requiredClientStorage) |
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
SmaccComponentType * | createSiblingComponent (TArgs... targs) |
template<typename SmaccComponentType , typename TOrthogonal , typename TClient , typename... TArgs> | |
SmaccComponentType * | createSiblingNamedComponent (std::string name, TArgs... targs) |
rclcpp::Node::SharedPtr | getNode () |
rclcpp::Logger | getLogger () const |
ISmaccStateMachine * | getStateMachine () |
![]() | |
![]() | |
ISmaccStateMachine * | stateMachine_ |
ISmaccClient * | owner_ |
Definition at line 44 of file cp_tf_listener.hpp.
cl_moveit2z::CpTFListener::CpTFListener | ( | ) |
|
inline |
Definition at line 80 of file cp_tf_listener.hpp.
|
inlineoverridevirtual |
Implements smacc2::ISmaccUpdatable.
Definition at line 49 of file cp_tf_listener.hpp.
References listenerMutex_, m_mutex_, poseTracks_, and tfListener_.
|
inline |
Definition at line 86 of file cp_tf_listener.hpp.
|
staticprivate |
Definition at line 94 of file cp_tf_listener.hpp.
Referenced by update().
|
private |
Definition at line 96 of file cp_tf_listener.hpp.
Referenced by update().
|
private |
Definition at line 97 of file cp_tf_listener.hpp.
Referenced by update().
|
staticprivate |
Definition at line 93 of file cp_tf_listener.hpp.
Referenced by update().