SMACC2
Loading...
Searching...
No Matches
smacc_client_async_behavior.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
23using namespace std::chrono_literals;
24
25namespace smacc2
26{
28{
29 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] asynchronous onEntry thread started");
30 this->onEntryThread_ = std::async(
31 std::launch::async,
32 [=]
33 {
34 this->onEntry();
35 this->postFinishEventFn_();
36 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] asynchronous onEntry thread finished");
37 return 0;
38 });
39}
40
42 std::optional<std::future<int>> & threadfut, bool requestFinish)
43{
44 try
45 {
46 rclcpp::Rate r(100);
47 while (rclcpp::ok())
48 {
49 //bool valid = threadfut.valid();
50 if (threadfut && threadfut->valid())
51 {
52 auto status = threadfut->wait_for(std::chrono::milliseconds(20));
53 if (status == std::future_status::ready)
54 {
55 // done
56 threadfut->get();
57 break;
58 }
59 else
60 {
61 // in progress
62 RCLCPP_INFO_STREAM(
63 getLogger(),
64 "[" << getName()
65 << "] fut valid but waiting for asynchronous onEntry thread to finish: state: "
66 << (int)status);
67 }
68 }
69 else
70 {
71 RCLCPP_INFO_STREAM(
72 getLogger(),
73 "[" << getName()
74 << "] waiting future onEntryThread. It was not even created. Skipping wait.");
75 break;
76 }
77
78 // r.sleep();
79 rclcpp::sleep_for(100ms);
80 // rclcpp::spin_some(getNode());
81 RCLCPP_WARN_THROTTLE(
82 getLogger(), *(getNode()->get_clock()), 1000,
83 "[%s] waiting for finishing client behavior, before leaving the state. Is the client "
84 "behavior stuck? requesting force finish",
85 this->getName().c_str());
86
87 if (requestFinish) requestForceFinish();
88 }
89 }
90 catch (const std::exception & e)
91 {
92 RCLCPP_DEBUG(
93 getLogger(),
94 "[SmaccAsyncClientBehavior] trying to join function, but it was already finished.");
95 }
96}
97
99{
100 waitFutureIfNotFinished(this->onEntryThread_, requestFinish);
101}
102
104{
105 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] onExit - join async onEntry thread");
106 this->waitOnEntryThread(true);
107
108 RCLCPP_INFO_STREAM(
109 getLogger(), "[" << getName() << "] onExit - Creating asynchronous onExit thread");
110 this->onExitThread_ = std::async(
111 std::launch::async,
112 [=]
113 {
114 this->onExit();
115 RCLCPP_INFO_STREAM(getLogger(), "[" << getName() << "] asynchronous onExit done.");
116 return 0;
117 });
118}
119
121{
122 RCLCPP_DEBUG_STREAM(
123 getLogger(), "[" << getName()
124 << "] Destroying client behavior- Waiting finishing of asynchronous onExit "
125 "thread");
126 try
127 {
128 if (this->onExitThread_)
129 {
130 // this->onExitThread_->get();
131 this->onExitThread_->get();
132 }
133 //this->onExitThread_->get();
134 }
135 catch (...)
136 {
137 RCLCPP_DEBUG(
138 getLogger(),
139 "[SmaccAsyncClientBehavior] trying to Join onExit function, but it was already "
140 "finished.");
141 }
142
143 RCLCPP_DEBUG_STREAM(
144 getLogger(), "[" << getName()
145 << "] Destroying client behavior- onExit thread finished. Proccedding "
146 "destruction.");
147}
148
150
152
154
156{
157 RCLCPP_INFO_STREAM_THROTTLE(
158 getLogger(), *(getNode()->get_clock()), 1000, "[" << getName() << "] requestForceFinish");
160}
161
162} // namespace smacc2
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
std::optional< std::future< int > > onExitThread_
std::optional< std::future< int > > onEntryThread_
void waitFutureIfNotFinished(std::optional< std::future< int > > &threadfut, bool requestFinish)