.. _program_listing_file__tmp_ws_src_cascade_lifecycle_rclcpp_cascade_lifecycle_include_rclcpp_cascade_lifecycle_rclcpp_cascade_lifecycle.hpp: Program Listing for File rclcpp_cascade_lifecycle.hpp ===================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/cascade_lifecycle/rclcpp_cascade_lifecycle/include/rclcpp_cascade_lifecycle/rclcpp_cascade_lifecycle.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2020 Intelligent Robotics Lab // // 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. #ifndef RCLCPP_CASCADE_LIFECYCLE__RCLCPP_CASCADE_LIFECYCLE_HPP_ #define RCLCPP_CASCADE_LIFECYCLE__RCLCPP_CASCADE_LIFECYCLE_HPP_ #include #include #include #include "rclcpp/node_options.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp_lifecycle/visibility_control.h" #include "rclcpp_lifecycle/node_interfaces/lifecycle_node_interface.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "cascade_lifecycle_msgs/msg/activation.hpp" #include "cascade_lifecycle_msgs/msg/state.hpp" #include "rclcpp/macros.hpp" #include "rclcpp/rclcpp.hpp" namespace rclcpp_cascade_lifecycle { class CascadeLifecycleNode : public rclcpp_lifecycle::LifecycleNode { public: RCLCPP_LIFECYCLE_PUBLIC explicit CascadeLifecycleNode( const std::string & node_name, const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); RCLCPP_LIFECYCLE_PUBLIC CascadeLifecycleNode( const std::string & node_name, const std::string & namespace_, const rclcpp::NodeOptions & options = rclcpp::NodeOptions()); void add_activation(const std::string & node_name); void remove_activation(const std::string & node_name); void clear_activation(); const std::set & get_activators() const {return activators_;} const std::set & get_activations() const {return activations_;} const std::map & get_activators_state() const { return activators_state_; } private: rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_configure_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_cleanup_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_shutdown_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_activate_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_deactivate_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn on_error_internal(const rclcpp_lifecycle::State & previous_state); rclcpp_lifecycle::LifecyclePublisher::SharedPtr states_pub_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr activations_pub_; rclcpp::Subscription::SharedPtr activations_sub_; rclcpp::Subscription::SharedPtr states_sub_; rclcpp::TimerBase::SharedPtr timer_; std::set activators_; std::set activations_; std::map activators_state_; void activations_callback(const cascade_lifecycle_msgs::msg::Activation::SharedPtr msg); void states_callback(const cascade_lifecycle_msgs::msg::State::SharedPtr msg); void update_state(); void timer_callback(); }; } // namespace rclcpp_cascade_lifecycle #endif // RCLCPP_CASCADE_LIFECYCLE__RCLCPP_CASCADE_LIFECYCLE_HPP_