.. _program_listing_file_include_service_wrapper.hpp: Program Listing for File service_wrapper.hpp ============================================ |exhale_lsh| :ref:`Return to documentation for file ` (``include/service_wrapper.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp #ifndef RIG_RECONFIGURE_SERVICE_WRAPPER_HPP #define RIG_RECONFIGURE_SERVICE_WRAPPER_HPP #include #include #include #include #include #include "queue.hpp" #include "requests.hpp" #include "responses.hpp" struct FutureTimeoutContainer { FutureTimeoutContainer() { timeSent = std::chrono::system_clock::now(); } std::chrono::time_point timeSent; bool handled = false; bool timeoutReached = false; }; class ServiceWrapper { public: explicit ServiceWrapper(bool ignoreDefaultParameters_ = true); void terminate(); void setNodeOfInterest(const std::string &name); void pushRequest(RequestPtr &&request); ResponsePtr tryPopResponse(); void checkForTimeouts(); void setIgnoreDefaultParameters(bool ignoreDefaultParameters); private: void threadFunc(); void handleRequest(const RequestPtr &request); Queue requestQueue; Queue responseQueue; std::atomic_bool terminateThread = false; bool ignoreDefaultParameters; std::string nodeName; std::thread thread; std::thread rosThread; std::promise terminationHelper; std::mutex unfinishedROSRequestsMutex; std::vector> unfinishedROSRequests; std::shared_ptr node; rclcpp::executors::SingleThreadedExecutor executor; // clients for calling the different services rclcpp::Client::SharedPtr listParametersClient; rclcpp::Client::SharedPtr getParametersClient; rclcpp::Client::SharedPtr setParametersClient; // callbacks for the results of the futures void nodeParametersReceived(const rclcpp::Client::SharedFuture &future, const std::shared_ptr &timeoutContainer); void parameterValuesReceived(const rclcpp::Client::SharedFuture &future, const std::vector ¶meterNames, const std::shared_ptr &timeoutContainer); void parameterModificationResponseReceived(const rclcpp::Client::SharedFuture &future, const std::string ¶meterName, const std::shared_ptr &timeoutContainer); }; #endif // RIG_RECONFIGURE_SERVICE_WRAPPER_HPP