.. _program_listing_file__tmp_ws_src_ros2_planning_system_plansys2_executor_include_plansys2_executor_ExecutorNode.hpp: Program Listing for File ExecutorNode.hpp ========================================= |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ros2_planning_system/plansys2_executor/include/plansys2_executor/ExecutorNode.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright 2019 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 PLANSYS2_EXECUTOR__EXECUTORNODE_HPP_ #define PLANSYS2_EXECUTOR__EXECUTORNODE_HPP_ #include #include #include #include #include "plansys2_domain_expert/DomainExpertClient.hpp" #include "plansys2_problem_expert/ProblemExpertClient.hpp" #include "plansys2_planner/PlannerClient.hpp" #include "plansys2_executor/ActionExecutor.hpp" #include "lifecycle_msgs/msg/state.hpp" #include "lifecycle_msgs/msg/transition.hpp" #include "plansys2_msgs/action/execute_plan.hpp" #include "plansys2_msgs/msg/action_execution_info.hpp" #include "plansys2_msgs/srv/get_ordered_sub_goals.hpp" #include "plansys2_msgs/msg/plan.hpp" #include "std_msgs/msg/string.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" #include "rclcpp_lifecycle/lifecycle_node.hpp" #include "rclcpp_lifecycle/lifecycle_publisher.hpp" namespace plansys2 { class ExecutorNode : public rclcpp_lifecycle::LifecycleNode { public: using ExecutePlan = plansys2_msgs::action::ExecutePlan; using GoalHandleExecutePlan = rclcpp_action::ServerGoalHandle; using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn; ExecutorNode(); CallbackReturnT on_configure(const rclcpp_lifecycle::State & state); CallbackReturnT on_activate(const rclcpp_lifecycle::State & state); CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state); CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state); CallbackReturnT on_shutdown(const rclcpp_lifecycle::State & state); CallbackReturnT on_error(const rclcpp_lifecycle::State & state); void get_ordered_sub_goals_service_callback( const std::shared_ptr request_header, const std::shared_ptr request, const std::shared_ptr response); void get_plan_service_callback( const std::shared_ptr request_header, const std::shared_ptr request, const std::shared_ptr response); protected: rclcpp::Node::SharedPtr node_; rclcpp::Node::SharedPtr aux_node_; bool cancel_plan_requested_; std::optional current_plan_; std::optional> ordered_sub_goals_; std::string action_bt_xml_; std::shared_ptr domain_client_; std::shared_ptr problem_client_; std::shared_ptr planner_client_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr execution_info_pub_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr executing_plan_pub_; rclcpp_action::Server::SharedPtr execute_plan_action_server_; rclcpp::Service::SharedPtr get_ordered_sub_goals_service_; rclcpp_lifecycle::LifecyclePublisher::SharedPtr dotgraph_pub_; std::optional> getOrderedSubGoals(); rclcpp::Service::SharedPtr get_plan_service_; rclcpp_action::GoalResponse handle_goal( const rclcpp_action::GoalUUID & uuid, std::shared_ptr goal); rclcpp_action::CancelResponse handle_cancel( const std::shared_ptr goal_handle); void execute(const std::shared_ptr goal_handle); void handle_accepted(const std::shared_ptr goal_handle); std::vector get_feedback_info( std::shared_ptr> action_map); void print_execution_info( std::shared_ptr> exec_info); }; } // namespace plansys2 #endif // PLANSYS2_EXECUTOR__EXECUTORNODE_HPP_