.. _program_listing_file__tmp_ws_src_system_modes_system_modes_include_system_modes_mode_observer.hpp: Program Listing for File mode_observer.hpp ========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/system_modes/system_modes/include/system_modes/mode_observer.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright (c) 2018 - for information on the respective copyright owner // see the NOTICE file and/or the repository https://github.com/microros/system_modes // // 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 #include #include #include #include "system_modes/mode.hpp" #include "system_modes_msgs/msg/mode_event.hpp" #include "system_modes_msgs/srv/get_mode.hpp" namespace system_modes { using std::map; using std::mutex; using std::string; using lifecycle_msgs::msg::TransitionEvent; using lifecycle_msgs::srv::GetState; using rclcpp::node_interfaces::NodeBaseInterface; using system_modes_msgs::msg::ModeEvent; using system_modes_msgs::srv::GetMode; class ModeObserver { public: explicit ModeObserver(std::weak_ptr); virtual ~ModeObserver() = default; virtual StateAndMode get(const string & part_name); virtual void observe(const string & part_name); virtual void stop_observing(const string & part_name); protected: virtual void transition_callback( const TransitionEvent::SharedPtr msg, const string & part_name); virtual void mode_event_callback( const ModeEvent::SharedPtr msg, const string & part_name); private: std::weak_ptr node_handle_; map cache_; mutable std::shared_timed_mutex mutex_; map>> state_subs_; map>> mode_subs_; }; } // namespace system_modes