SMACC2
Loading...
Searching...
No Matches
cb_wait_topic_message.hpp
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
21#pragma once
22
23#include <functional>
24#include <rclcpp/rclcpp.hpp>
26
27namespace smacc2
28{
29namespace client_behaviors
30{
31using namespace std::chrono_literals;
32
33// Asynchronous behavior that waits to a topic message to send EvCbSuccess event
34// a guard function can be set to use conditions on the contents
35template <typename TMessage>
37{
38public:
40 const char * topicname, std::function<bool(const TMessage &)> guardFunction = nullptr)
41 {
42 topicname_ = topicname;
43 guardFn_ = guardFunction;
44 }
45
47
48 void onEntry() override
49 {
50 rclcpp::SensorDataQoS qos;
51 // qos.reliable();
52 // rclcpp::SubscriptionOptions sub_option;
53 RCLCPP_INFO_STREAM(
54 getLogger(), "[CbWaitTopicMessage] waiting message from topic: "
55 << topicname_ << "[" << demangledTypeName<TMessage>() << "]");
56
57 // sub_ = getNode()->create_subscription<TMessage>(
58 // topicname_, qos,
59 // std::bind(&CbWaitTopicMessage<TMessage>::onMessageReceived, this, std::placeholders::_1),
60 // sub_option);
61
62 std::function<void(typename TMessage::SharedPtr)> fn = [this](auto msg)
63 { this->onMessageReceived(msg); };
64
65 auto nh = getNode();
66 sub_ = nh->create_subscription<TMessage>(topicname_, qos, fn);
67 }
68
69 void onMessageReceived(const typename TMessage::SharedPtr msg)
70 {
71 if (guardFn_ == nullptr || guardFn_(*msg))
72 {
73 RCLCPP_INFO(getLogger(), "[CbWaitTopicMessage] message received.");
74 success = true;
75 this->postSuccessEvent();
76 }
77 }
78
79protected:
80 bool success = false;
81 typename rclcpp::Subscription<TMessage>::SharedPtr sub_;
82 std::function<bool(const TMessage &)> guardFn_;
83 std::string topicname_;
84};
85} // namespace client_behaviors
86} // namespace smacc2
virtual rclcpp::Node::SharedPtr getNode()
void onMessageReceived(const typename TMessage::SharedPtr msg)
CbWaitTopicMessage(const char *topicname, std::function< bool(const TMessage &)> guardFunction=nullptr)
std::function< bool(const TMessage &)> guardFn_
rclcpp::Subscription< TMessage >::SharedPtr sub_