.. _program_listing_file__tmp_ws_src_rmf_simulation_rmf_robot_sim_common_include_rmf_robot_sim_common_ingestor_common.hpp: Program Listing for File ingestor_common.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/rmf_simulation/rmf_robot_sim_common/include/rmf_robot_sim_common/ingestor_common.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp /* * Copyright (C) 2020 Open Source Robotics Foundation * * 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 RMF_ROBOT_SIM_COMMON__INGESTOR_COMMON_HPP #define RMF_ROBOT_SIM_COMMON__INGESTOR_COMMON_HPP #include #include #include #include #include #include #include #include #include using namespace rmf_plugins_utils; namespace rmf_ingestor_common { class TeleportIngestorCommon { public: using FleetState = rmf_fleet_msgs::msg::FleetState; using FleetStateIt = std::unordered_map::iterator; using IngestorState = rmf_ingestor_msgs::msg::IngestorState; using IngestorRequest = rmf_ingestor_msgs::msg::IngestorRequest; using IngestorResult = rmf_ingestor_msgs::msg::IngestorResult; // Ingest request params bool ingest = false; IngestorRequest latest; // Ingestor params std::string _guid; bool ingestor_filled = false; double last_pub_time = 0.0; double last_ingested_time = 0.0; double sim_time = 0.0; rclcpp::Node::SharedPtr ros_node; std::unordered_map non_static_models_init_poses; std::unordered_map fleet_states; IngestorState current_state; void send_ingestor_response(uint8_t status) const; void fleet_state_cb(FleetState::UniquePtr msg); void ingestor_request_cb(IngestorRequest::UniquePtr msg); void on_update( std::function&)> fill_robot_list_cb, std::function&, bool&)> find_nearest_model_cb, std::function get_payload_model_cb, std::function transport_model_cb, std::function send_ingested_item_home_cb); void init_ros_node(const rclcpp::Node::SharedPtr node); private: rclcpp::Subscription::SharedPtr _fleet_state_sub; rclcpp::Publisher::SharedPtr _state_pub; rclcpp::Subscription::SharedPtr _request_sub; rclcpp::Publisher::SharedPtr _result_pub; std::unordered_map _past_request_guids; bool ingest_from_nearest_robot( std::function&)> fill_robot_list_cb, std::function&, bool&)> find_nearest_model_cb, std::function get_payload_model_cb, std::function transport_model_cb, const std::string& fleet_name); }; } // namespace rmf_ingestor_common #endif