SMACC2
cl_multirole_sensor.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#pragma once
16
17#include <optional>
18#include <rclcpp/rclcpp.hpp>
22
24{
25using namespace smacc2;
26
27template <typename TSource, typename TOrthogonal>
28struct EvTopicMessageTimeout : sc::event<EvTopicMessageTimeout<TSource, TOrthogonal>>
29{
30};
31
32using namespace smacc2::client_bases;
33
34// This class extends a ros topic subscriber object that reads from
35// some sensor source. It provides timeout event.
36template <typename MessageType>
38{
39public:
40 typedef MessageType TMessageType;
42
43 ClMultiroleSensor() : smacc2::client_bases::SmaccSubscriberClient<MessageType>()
44 {
45 initialized_ = false;
46 }
47
48 template <typename T>
49 boost::signals2::connection onMessageTimeout(void (T::*callback)(), T * object)
50 {
51 return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object);
52 }
53
54 std::function<void()> postTimeoutMessageEvent;
55
56 template <typename TOrthogonal, typename TSourceObject>
58 {
60 TOrthogonal, TSourceObject>();
61
62 this->postTimeoutMessageEvent = [this]() {
63 this->onMessageTimeout_();
64
66 this->postEvent(event);
67 };
68 }
69
70 void onInitialize() override
71 {
72 if (!initialized_)
73 {
75
77
78 if (timeout_)
79 {
80 auto ros_clock = rclcpp::Clock::make_shared();
81 timeoutTimer_ = rclcpp::create_timer(
82 this->getNode(), this->getNode()->get_clock(), *timeout_,
84
85 timeoutTimer_->reset();
86 }
87 else
88 {
89 RCLCPP_WARN(
90 this->getLogger(),
91 "Timeout sensor client not set, skipping timeout watchdog funcionality");
92 }
93
94 initialized_ = true;
95 }
96 }
97
98 std::optional<rclcpp::Duration> timeout_;
99
100protected:
101 void resetTimer(const MessageType & /*msg*/)
102 {
103 //resetting the timer
104 timeoutTimer_->reset();
105 //timeoutTimer_->stop();
106 //timeoutTimer_->start();
107 }
108
109private:
110 rclcpp::TimerBase::SharedPtr timeoutTimer_;
112
114};
115} // namespace cl_multirole_sensor
rclcpp::TimerBase::SharedPtr timeoutTimer_
boost::signals2::connection onMessageTimeout(void(T::*callback)(), T *object)
std::optional< rclcpp::Duration > timeout_
rclcpp::Node::SharedPtr getNode()
Definition: client.cpp:60
ISmaccStateMachine * getStateMachine()
rclcpp::Logger getLogger()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)
void callback(const image_tools::ROSCvMatContainer &img)