SMACC
Loading...
Searching...
No Matches
smacc_client_async_behavior.cpp
Go to the documentation of this file.
2
3namespace smacc
4{
6 {
7 ROS_INFO_STREAM("[" << getName() << "] Creating asynchronous onEntry thread");
8 this->onEntryThread_ = std::async(std::launch::async,
9 [=] {
10 this->onEntry();
11 this->postFinishEventFn_();
12 return 0;
13 });
14 }
15
17 {
18 ROS_INFO_STREAM("[" << getName() << "] onExit - join async onEntry thread");
19
20 try
21 {
22 ros::Rate r(200);
23 while (ros::ok())
24 {
25 bool valid = this->onEntryThread_.valid();
26 if (valid)
27 {
28 auto status = this->onEntryThread_.wait_for(std::chrono::milliseconds(20));
29 if (status == std::future_status::ready)
30 {
31 this->onEntryThread_.get();
32 break;
33 }
34 }
35
36 r.sleep();
37 ros::spinOnce();
38 ROS_DEBUG("waiting for finishing client behavior");
39 }
40 }
41 catch (const std::exception &e)
42 {
43 ROS_DEBUG("[SmaccAsyncClientBehavior] trying to Join onEntry function, but it was already finished.");
44 }
45
46 ROS_INFO_STREAM("[" << getName() << "] onExit - Creating asynchronous onExit thread");
47 this->onExitThread_ = std::async(std::launch::async,
48 [=] {
49 this->onExit();
50 return 0;
51 });
52 }
53
55 {
56 ROS_DEBUG_STREAM("[" << getName() << "] Destroying client behavior- Waiting finishing of asynchronous onExit thread");
57 try
58 {
59 this->onExitThread_.get();
60 }
61 catch (...)
62 {
63 ROS_DEBUG("[SmaccAsyncClientBehavior] trying to Join onExit function, but it was already finished.");
64 }
65
66 ROS_DEBUG_STREAM("[" << getName() << "] Destroying client behavior- onExit thread finished. Proccedding destruction.");
67 }
68
70 {
71 }
72
74 {
76 }
77
79 {
81 }
82
83} // namespace smacc