.. _program_listing_file__tmp_ws_src_SMACC2_smacc2_client_library_multirole_sensor_client_include_multirole_sensor_client_cl_multirole_sensor.hpp: Program Listing for File cl_multirole_sensor.hpp ================================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/SMACC2/smacc2_client_library/multirole_sensor_client/include/multirole_sensor_client/cl_multirole_sensor.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2021 RobosoftAI Inc. // // Licensed under the Apache License, Version 2.0 (the "License"); // you may not use this file except in compliance with the License. // You may obtain a copy of the License at // // http://www.apache.org/licenses/LICENSE-2.0 // // Unless required by applicable law or agreed to in writing, software // distributed under the License is distributed on an "AS IS" BASIS, // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. // See the License for the specific language governing permissions and // limitations under the License. #pragma once #include #include #include #include #include namespace cl_multirole_sensor { using namespace smacc2; template struct EvTopicMessageTimeout : sc::event> { }; using namespace smacc2::client_bases; // This class extends a ros topic subscriber object that reads from // some sensor source. It provides timeout event. template class ClMultiroleSensor : public smacc2::client_bases::SmaccSubscriberClient { public: typedef MessageType TMessageType; SmaccSignal onMessageTimeout_; ClMultiroleSensor() : smacc2::client_bases::SmaccSubscriberClient() { initialized_ = false; } template boost::signals2::connection onMessageTimeout(void (T::*callback)(), T * object) { return this->getStateMachine()->createSignalConnection(onMessageTimeout_, callback, object); } std::function postTimeoutMessageEvent; template void onOrthogonalAllocation() { SmaccSubscriberClient::template onOrthogonalAllocation< TOrthogonal, TSourceObject>(); this->postTimeoutMessageEvent = [this]() { this->onMessageTimeout_(); auto event = new EvTopicMessageTimeout(); this->postEvent(event); }; } void onInitialize() override { if (!initialized_) { SmaccSubscriberClient::onInitialize(); this->onMessageReceived(&ClMultiroleSensor::resetTimer, this); if (timeout_) { auto ros_clock = rclcpp::Clock::make_shared(); timeoutTimer_ = rclcpp::create_timer( this->getNode(), this->getNode()->get_clock(), *timeout_, std::bind(&ClMultiroleSensor::timeoutCallback, this)); timeoutTimer_->reset(); } else { RCLCPP_WARN( this->getLogger(), "Timeout sensor client not set, skipping timeout watchdog funcionality"); } initialized_ = true; } } std::optional timeout_; protected: void resetTimer(const MessageType & /*msg*/) { //resetting the timer timeoutTimer_->reset(); //timeoutTimer_->stop(); //timeoutTimer_->start(); } private: rclcpp::TimerBase::SharedPtr timeoutTimer_; bool initialized_; void timeoutCallback() { postTimeoutMessageEvent(); } }; } // namespace cl_multirole_sensor