.. _program_listing_file__tmp_ws_src_ros2_planning_system_plansys2_executor_include_plansys2_executor_ExecutorClient.hpp: Program Listing for File ExecutorClient.hpp =========================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/ros2_planning_system/plansys2_executor/include/plansys2_executor/ExecutorClient.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__EXECUTORCLIENT_HPP_ #define PLANSYS2_EXECUTOR__EXECUTORCLIENT_HPP_ #include #include #include #include #include "plansys2_msgs/action/execute_plan.hpp" #include "plansys2_msgs/srv/get_ordered_sub_goals.hpp" #include "plansys2_msgs/srv/get_plan.hpp" #include "plansys2_msgs/msg/plan.hpp" #include "plansys2_msgs/msg/tree.hpp" #include "rclcpp/rclcpp.hpp" #include "rclcpp_action/rclcpp_action.hpp" namespace plansys2 { class ExecutorClient { public: using ExecutePlan = plansys2_msgs::action::ExecutePlan; using GoalHandleExecutePlan = rclcpp_action::ClientGoalHandle; ExecutorClient(); explicit ExecutorClient(const std::string & node_name); bool start_plan_execution(const plansys2_msgs::msg::Plan & plan); bool execute_and_check_plan(); void cancel_plan_execution(); std::vector getOrderedSubGoals(); std::optional getPlan(); ExecutePlan::Feedback getFeedBack() {return feedback_;} std::optional getResult(); private: rclcpp::Node::SharedPtr node_; rclcpp_action::Client::SharedPtr action_client_; rclcpp::Client::SharedPtr get_ordered_sub_goals_client_; rclcpp::Client::SharedPtr get_plan_client_; ExecutePlan::Feedback feedback_; rclcpp_action::ClientGoalHandle::SharedPtr goal_handle_; rclcpp_action::ClientGoalHandle::WrappedResult result_; bool goal_result_available_{false}; bool executing_plan_{false}; void result_callback(const GoalHandleExecutePlan::WrappedResult & result); void feedback_callback( GoalHandleExecutePlan::SharedPtr goal_handle, const std::shared_ptr feedback); bool on_new_goal_received(const plansys2_msgs::msg::Plan & plan); bool should_cancel_goal(); void createActionClient(); }; } // namespace plansys2 #endif // PLANSYS2_EXECUTOR__EXECUTORCLIENT_HPP_