23using namespace std::chrono_literals;
29 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] asynchronous onEntry thread started");
36 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] asynchronous onEntry thread finished");
42 std::optional<std::future<int>> & threadfut,
bool requestFinish)
50 if (threadfut && threadfut->valid())
52 auto status = threadfut->wait_for(std::chrono::milliseconds(20));
53 if (status == std::future_status::ready)
65 <<
"] fut valid but waiting for asynchronous onEntry thread to finish: state: "
74 <<
"] waiting future onEntryThread. It was not even created. Skipping wait.");
79 rclcpp::sleep_for(100ms);
83 "[%s] waiting for finishing client behavior, before leaving the state. Is the client "
84 "behavior stuck? requesting force finish",
90 catch (
const std::exception & e)
94 "[SmaccAsyncClientBehavior] trying to join function, but it was already finished.");
105 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] onExit - join async onEntry thread");
109 getLogger(),
"[" <<
getName() <<
"] onExit - Creating asynchronous onExit thread");
115 RCLCPP_INFO_STREAM(
getLogger(),
"[" <<
getName() <<
"] asynchronous onExit done.");
124 <<
"] Destroying client behavior- Waiting finishing of asynchronous onExit "
139 "[SmaccAsyncClientBehavior] trying to Join onExit function, but it was already "
145 <<
"] Destroying client behavior- onExit thread finished. Proccedding "
157 RCLCPP_INFO_STREAM_THROTTLE(
std::string getName() const
virtual rclcpp::Logger getLogger() const
virtual rclcpp::Node::SharedPtr getNode() const
virtual ~SmaccAsyncClientBehavior()
bool isShutdownRequested_
std::function< void()> postSuccessEventFn_
std::function< void()> postFinishEventFn_
void executeOnEntry() override
virtual void dispose() override
std::optional< std::future< int > > onExitThread_
std::optional< std::future< int > > onEntryThread_
void waitFutureIfNotFinished(std::optional< std::future< int > > &threadfut, bool requestFinish)
void requestForceFinish()
void executeOnExit() override
std::function< void()> postFailureEventFn_
void waitOnEntryThread(bool requestFinish)