#include <cb_wait_transform.hpp>
|
| CbWaitTransform (std::string targetFrame, std::string referenceFrame, rclcpp::Duration timeout) |
|
virtual | ~CbWaitTransform () |
|
template<typename TOrthogonal , typename TSourceObject > |
void | onOrthogonalAllocation () |
|
void | onEntry () override |
|
template<typename TOrthogonal , typename TSourceObject > |
void | onOrthogonalAllocation () |
|
virtual | ~SmaccAsyncClientBehavior () |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onSuccess (TCallback callback, T *object) |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onFinished (TCallback callback, T *object) |
|
template<typename TCallback , typename T > |
boost::signals2::connection | onFailure (TCallback callback, T *object) |
|
void | requestForceFinish () |
|
void | executeOnEntry () override |
|
void | executeOnExit () override |
|
void | waitOnEntryThread (bool requestFinish) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onSuccess (TCallbackMethod callback, T *object) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onFinished (TCallbackMethod callback, T *object) |
|
template<typename TCallbackMethod , typename T > |
boost::signals2::connection | onFailure (TCallbackMethod callback, T *object) |
|
| ISmaccClientBehavior () |
|
virtual | ~ISmaccClientBehavior () |
|
ISmaccStateMachine * | getStateMachine () |
|
std::string | getName () const |
|
template<typename SmaccClientType > |
void | requiresClient (SmaccClientType *&storage) |
|
template<typename SmaccComponentType > |
void | requiresComponent (SmaccComponentType *&storage, bool throwExceptionIfNotExist=false) |
|
virtual void | onExit () |
|
Definition at line 34 of file cb_wait_transform.hpp.
◆ CbWaitTransform()
cl_nav2z::CbWaitTransform::CbWaitTransform |
( |
std::string |
targetFrame, |
|
|
std::string |
referenceFrame, |
|
|
rclcpp::Duration |
timeout |
|
) |
| |
◆ ~CbWaitTransform()
cl_nav2z::CbWaitTransform::~CbWaitTransform |
( |
| ) |
|
|
virtual |
◆ onEntry()
void cl_nav2z::CbWaitTransform::onEntry |
( |
| ) |
|
|
overridevirtual |
Reimplemented from smacc2::ISmaccClientBehavior.
Definition at line 32 of file cb_wait_transform.cpp.
33{
34 RCLCPP_INFO(
37
40
41 tf2::Stamped<tf2::Transform> transform;
42 try
43 {
44 auto transformstamped =
46 tf2::fromMsg(transformstamped, transform);
47
49
50 RCLCPP_INFO(
51 getLogger(),
"[CbWaitTransform] Success wait transform ref %s -> target %s",
54 }
55 catch (tf2::TransformException & ex)
56 {
57 RCLCPP_ERROR_STREAM(
58 getLogger(),
"[CbWaitTransform] Failure waiting transform ( ref "
61 }
62}
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
References smacc2::ISmaccClientBehavior::getLogger(), smacc2::ISmaccClientBehavior::getNode(), smacc2::SmaccAsyncClientBehavior::postFailureEvent(), smacc2::SmaccAsyncClientBehavior::postSuccessEvent(), referenceFrame_, result_, targetFrame_, tfBuffer_, tfListener_, and timeout_.
◆ onOrthogonalAllocation()
template<typename TOrthogonal , typename TSourceObject >
void cl_nav2z::CbWaitTransform::onOrthogonalAllocation |
( |
| ) |
|
|
inline |
Definition at line 42 of file cb_wait_transform.hpp.
43 {
44 smacc2::SmaccAsyncClientBehavior::onOrthogonalAllocation<TOrthogonal, TSourceObject>();
45 }
◆ referenceFrame_
std::string cl_nav2z::CbWaitTransform::referenceFrame_ |
|
protected |
◆ result_
std::optional<tf2::Stamped<tf2::Transform> > cl_nav2z::CbWaitTransform::result_ |
|
protected |
◆ targetFrame_
std::string cl_nav2z::CbWaitTransform::targetFrame_ |
|
protected |
◆ tfBuffer_
std::shared_ptr<tf2_ros::Buffer> cl_nav2z::CbWaitTransform::tfBuffer_ |
|
protected |
◆ tfListener_
std::shared_ptr<tf2_ros::TransformListener> cl_nav2z::CbWaitTransform::tfListener_ |
|
protected |
◆ timeout_
rclcpp::Duration cl_nav2z::CbWaitTransform::timeout_ |
|
protected |
The documentation for this class was generated from the following files:
- smacc2_client_library/nav2z_client/nav2z_client/include/nav2z_client/client_behaviors/cb_wait_transform.hpp
- smacc2_client_library/nav2z_client/nav2z_client/src/nav2z_client/client_behaviors/cb_wait_transform.cpp