SMACC2
Loading...
Searching...
No Matches
cp_message_timeout.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>
20#include <smacc2/component.hpp>
22
23namespace cl_generic_sensor
24{
25namespace components
26{
27using namespace smacc2;
28
29// Timeout event definition
30template <typename TSource, typename TOrthogonal>
31struct EvTopicMessageTimeout : sc::event<EvTopicMessageTimeout<TSource, TOrthogonal>>
32{
33};
34
35// Component that monitors topic message reception and posts timeout events
36// when messages are not received within the specified duration
37template <typename MessageType>
39{
40public:
41 typedef MessageType TMessageType;
42
43 // Timeout signal - triggered when timeout occurs
45
46 // Optional timeout duration configuration
47 std::optional<rclcpp::Duration> timeout_;
48
50
51 virtual ~CpMessageTimeout() {}
52
53 // Signal subscription method for timeout events
54 template <typename T>
55 boost::signals2::connection onMessageTimeout(void (T::*callback)(), T * object)
56 {
57 return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object);
58 }
59
60 // Function to post timeout event - set during orthogonal allocation
61 std::function<void()> postTimeoutMessageEvent;
62
63 // Template method called during state orthogonal allocation
64 template <typename TOrthogonal, typename TSourceObject>
66 {
67 // Setup the event posting function with proper template types
68 this->postTimeoutMessageEvent = [this]()
69 {
70 // Emit signal
71 this->onMessageTimeout_();
72
73 // Post SMACC event
75 this->postEvent(event);
76 };
77
78 // Require the CpTopicSubscriber component to monitor messages
80 this->requiresComponent(subscriberComponent);
81
82 // Subscribe to message received signal to reset timer
84 }
85
86 // Initialize the timeout timer
87 void onInitialize() override
88 {
89 if (!initialized_)
90 {
91 if (timeout_)
92 {
93 RCLCPP_INFO_STREAM(
94 getLogger(), "[" << this->getName()
95 << "] Initializing message timeout watchdog with duration: "
96 << timeout_->seconds() << "s");
97
98 // Create the timeout timer
99 timeoutTimer_ = rclcpp::create_timer(
100 this->getNode(), this->getNode()->get_clock(), *timeout_,
102
103 timeoutTimer_->reset();
104 }
105 else
106 {
107 RCLCPP_WARN(
108 getLogger(),
109 "[CpMessageTimeout] Timeout duration not set, skipping timeout watchdog functionality");
110 }
111
112 initialized_ = true;
113 }
114 }
115
116protected:
117 // Reset the timer when a message is received
118 void resetTimer(const MessageType & /*msg*/)
119 {
120 if (timeoutTimer_)
121 {
122 timeoutTimer_->reset();
123 }
124 }
125
126private:
127 rclcpp::TimerBase::SharedPtr timeoutTimer_;
129
130 // Timer callback - invoked when timeout occurs
132 {
133 RCLCPP_WARN(
134 getLogger(), "[CpMessageTimeout] Message timeout occurred after %f seconds",
135 timeout_->seconds());
136
138 {
140 }
141 }
142};
143
144} // namespace components
145} // namespace cl_generic_sensor
boost::signals2::connection onMessageTimeout(void(T::*callback)(), T *object)
ISmaccStateMachine * getStateMachine()
virtual std::string getName() const
rclcpp::Logger getLogger() const
void requiresComponent(TComponent *&requiredComponentStorage, ComponentRequirement requirementType=ComponentRequirement::SOFT)
rclcpp::Node::SharedPtr getNode()
boost::signals2::connection createSignalConnection(TSmaccSignal &signal, TMemberFunctionPrototype callback, TSmaccObjectType *object)
boost::signals2::connection onMessageReceived(void(T::*callback)(const MessageType &), T *object)