SMACC2
Loading...
Searching...
No Matches
cb_wait_action_server_2.hpp
Go to the documentation of this file.
1// Copyright 2021 RobosoftAI Inc.
2//
3// Licensed under the Apache License, Version 2.0 (the "License");
4// you may not use this file except in compliance with the License.
5// You may obtain a copy of the License at
6//
7// http://www.apache.org/licenses/LICENSE-2.0
8//
9// Unless required by applicable law or agreed to in writing, software
10// distributed under the License is distributed on an "AS IS" BASIS,
11// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12// See the License for the specific language governing permissions and
13// limitations under the License.
14
15/*****************************************************************************************************************
16 *
17 * Authors: Pablo Inigo Blasco, Brett Aldrich
18 *
19 ******************************************************************************************************************/
20
21#pragma once
22
26
27namespace smacc2
28{
29namespace client_behaviors
30{
31using namespace smacc2::client_bases;
32using namespace smacc2::client_core_components;
33
34// waits the action server is available in the current orthogonal
35template <typename ActionT>
37{
38public:
39 template <typename TOrthogonal, typename TSourceObject>
46
47 CbWaitActionServer2(std::chrono::milliseconds timeout) : timeout_(timeout) {}
48
50
51 void onEntry()
52 {
53 if (cp_action_client_ != nullptr)
54 {
55 RCLCPP_INFO(
56 getLogger(), "[CbWaitActionServer] waiting for action server (using CpActionClient)...");
57 bool found = false;
58 auto starttime = getNode()->now();
59 while (!this->isShutdownRequested() && !found && (getNode()->now() - starttime) < timeout_)
60 {
61 auto client_base = cp_action_client_->getActionClient();
62 found = client_base->wait_for_action_server(std::chrono::milliseconds(1000));
63 }
64
65 if (found)
66 {
67 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] action server already available");
68 this->postSuccessEvent();
69 }
70 else
71 {
72 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] action server not found, timeout");
73 this->postFailureEvent();
74 }
75 }
76 else
77 {
78 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] there is no action client in this orthogonal");
79 this->postFailureEvent();
80 }
81 }
82
83private:
85
86 std::chrono::milliseconds timeout_;
87};
88} // namespace client_behaviors
89} // namespace smacc2
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...
CbWaitActionServer2(std::chrono::milliseconds timeout)
std::shared_ptr< ActionClient > getActionClient() const