29namespace client_behaviors
35template <
typename ActionT>
39 template <
typename TOrthogonal,
typename TSourceObject>
56 getLogger(),
"[CbWaitActionServer] waiting for action server (using CpActionClient)...");
58 auto starttime =
getNode()->now();
62 found = client_base->wait_for_action_server(std::chrono::milliseconds(1000));
67 RCLCPP_INFO(
getLogger(),
"[CbWaitActionServer] action server already available");
72 RCLCPP_INFO(
getLogger(),
"[CbWaitActionServer] action server not found, timeout");
78 RCLCPP_INFO(
getLogger(),
"[CbWaitActionServer] there is no action client in this orthogonal");
void requiresComponent(SmaccComponentType *&storage, bool throwExceptionIfNotExist)
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
bool isShutdownRequested()
onEntry is executed in a new thread. However the current state cannot be left until the onEntry threa...
void onStateOrthogonalAllocation()
CpActionClient< ActionT > * cp_action_client_
CbWaitActionServer2(std::chrono::milliseconds timeout)
virtual ~CbWaitActionServer2()
void onStateOrthogonalAllocation()
std::chrono::milliseconds timeout_
std::shared_ptr< ActionClient > getActionClient() const