.. _program_listing_file__tmp_ws_src_locator_ros_bridge_bosch_locator_bridge_include_bosch_locator_bridge_locator_rpc_interface.hpp: Program Listing for File locator_rpc_interface.hpp ================================================== |exhale_lsh| :ref:`Return to documentation for file ` (``/tmp/ws/src/locator_ros_bridge/bosch_locator_bridge/include/bosch_locator_bridge/locator_rpc_interface.hpp``) .. |exhale_lsh| unicode:: U+021B0 .. UPWARDS ARROW WITH TIP LEFTWARDS .. code-block:: cpp // Copyright (c) 2021 - for information on the respective copyright owner // see the NOTICE file and/or the repository https://github.com/boschglobal/locator_ros_bridge. // // 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 BOSCH_LOCATOR_BRIDGE__LOCATOR_RPC_INTERFACE_HPP_ #define BOSCH_LOCATOR_BRIDGE__LOCATOR_RPC_INTERFACE_HPP_ #include #include #include #include #include #include class LocatorRPCInterface { public: LocatorRPCInterface(const std::string & host, uint16_t port); virtual ~LocatorRPCInterface(); void login(const std::string & user, const std::string & password); void refresh(); void logout(); std::string getAboutBuildList(); std::unordered_map> getAboutModules(); Poco::DynamicStruct getConfigList(); bool setConfigList(const Poco::DynamicStruct & config); Poco::JSON::Object getSessionQuery() const; Poco::JSON::Object call(const std::string & method, const Poco::JSON::Object & query_obj); protected: Poco::JSON::Object json_rpc_call( Poco::Net::HTTPClientSession & session, const std::string & method, const Poco::JSON::Object & query_obj); std::mutex json_rpc_call_mutex_; Poco::Net::HTTPClientSession session_; std::string session_id_; size_t query_id_; }; #endif // BOSCH_LOCATOR_BRIDGE__LOCATOR_RPC_INTERFACE_HPP_