SMACC2
Loading...
Searching...
No Matches
cb_wait_action_server.cpp
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
22
23namespace smacc2
24{
25namespace client_behaviors
26{
27CbWaitActionServer::CbWaitActionServer(std::chrono::milliseconds timeout) : timeout_(timeout) {}
28
30
32{
33 if (client_ != nullptr)
34 {
35 bool found = false;
36 auto starttime = getNode()->now();
37 while (!this->isShutdownRequested() && !found && (getNode()->now() - starttime) < timeout_)
38 {
39 std::shared_ptr<rclcpp_action::ClientBase> client_base = client_->getClientBase();
40 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] waiting action server..");
41 found = client_base->wait_for_action_server(std::chrono::milliseconds(1000));
42 }
43
44 if (found)
45 {
46 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] action server already available");
47 this->postSuccessEvent();
48 }
49 else
50 {
51 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] action server not found, timeout");
52 this->postFailureEvent();
53 }
54 }
55 else
56 {
57 RCLCPP_INFO(getLogger(), "[CbWaitActionServer] there is no action client in this orthogonal");
58 this->postFailureEvent();
59 }
60}
61} // namespace client_behaviors
62} // namespace smacc2
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...
virtual std::shared_ptr< rclcpp_action::ClientBase > getClientBase()=0
CbWaitActionServer(std::chrono::milliseconds timeout)