SMACC2
Loading...
Searching...
No Matches
cb_wait_topic.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{
27CbWaitTopic::CbWaitTopic(std::string nodeName) : topicName_(nodeName), rate_(5) {}
28
30
32{
33 bool found = false;
34 while (!this->isShutdownRequested() && !found)
35 {
37 getLogger(), *(getNode()->get_clock()), 1000,
38 "[" << getName() << "] waiting topic: " << topicName_);
39 std::stringstream ss;
40 auto topicnames = getNode()->get_topic_names_and_types();
41
42 for (auto & t : topicnames)
43 {
44 ss << t.first << std::endl;
45 if (t.first == topicName_)
46 {
47 found = true;
48 }
49 }
50
51 auto totalstr = ss.str();
53 getLogger(), *(getNode()->get_clock()), 5000,
54 "[" << getName() << "] still waiting topic " << topicName_ << ", listing topics ("
55 << topicnames.size() << ")" << std::endl
56 << totalstr);
57
58 rate_.sleep();
59 }
60
61 if (found)
62 {
63 this->postSuccessEvent();
64 }
65 else
66 {
67 this->postFailureEvent();
68 }
69}
70
71} // namespace client_behaviors
72} // 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...