NRP Core  1.4.1
nrp_ros_proxy.h
Go to the documentation of this file.
1 /* * NRP Core - Backend infrastructure to synchronize simulations
2  *
3  * Copyright 2020-2023 NRP Team
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License");
6  * you may not use this file except in compliance with the License.
7  * You may obtain a copy of the License at
8  *
9  * http://www.apache.org/licenses/LICENSE-2.0
10  *
11  * Unless required by applicable law or agreed to in writing, software
12  * distributed under the License is distributed on an "AS IS" BASIS,
13  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
14  * See the License for the specific language governing permissions and
15  * limitations under the License.
16  *
17  * This project has received funding from the European Union’s Horizon 2020
18  * Framework Programme for Research and Innovation under the Specific Grant
19  * Agreement No. 945539 (Human Brain Project SGA3).
20  */
21 
22 #ifndef ROS_PROXY_H
23 #define ROS_PROXY_H
24 
25 #include "ros/ros.h"
26 #include <boost/shared_ptr.hpp>
27 #include <boost/function.hpp>
28 #include <functional>
29 
30 class NRPROSProxy {
31 
32 public:
33 
34  // Delete move and copy operators. This ensures this class is a singleton
35  NRPROSProxy(const NRPROSProxy &) = delete;
36  NRPROSProxy(NRPROSProxy &&) = delete;
37 
38  NRPROSProxy &operator=(const NRPROSProxy &) = delete;
39  NRPROSProxy &operator=(NRPROSProxy &&) = delete;
40 
44  static NRPROSProxy &getInstance();
45 
49  static NRPROSProxy &resetInstance();
50 
54  template<class MSG_TYPE>
55  void subscribe(const std::string& address, const boost::function<void (const boost::shared_ptr<MSG_TYPE const>&)>& callback, size_t queueSize = 10)
56  { _subscribers.push_back(_node->subscribe<MSG_TYPE>(address, queueSize, callback)); }
57 
61  template<class MSG_TYPE>
62  void publish(const std::string& address, const MSG_TYPE& msg, size_t queueSize = 10)
63  {
64  if(!_publishers.count(address))
65  _publishers.emplace(address, _node->advertise<MSG_TYPE>(address, queueSize));
66 
67  _publishers[address].publish(msg);
68  }
69 
70 private:
71 
72  std::shared_ptr<ros::NodeHandle> _node;
73  std::map<std::string, ros::Publisher> _publishers;
74  std::vector<ros::Subscriber> _subscribers;
75 
79  NRPROSProxy()
80  { _node.reset(new ros::NodeHandle()); }
81 
82  static std::unique_ptr<NRPROSProxy> _instance;
83 
84 };
85 
86 #endif //ROS_PROXY_H
NRPROSProxy
Definition: nrp_ros_proxy.h:30
NRPROSProxy::resetInstance
static NRPROSProxy & resetInstance()
Reset singleton instance.
Definition: nrp_ros_proxy.cpp:31
NRPROSProxy::getInstance
static NRPROSProxy & getInstance()
Get singleton instance of NRPROSProxy.
Definition: nrp_ros_proxy.cpp:26
NRPROSProxy::subscribe
void subscribe(const std::string &address, const boost::function< void(const boost::shared_ptr< MSG_TYPE const > &)> &callback, size_t queueSize=10)
Subscribe to ROS topic 'address' with callback function 'callback'.
Definition: nrp_ros_proxy.h:55
NRPROSProxy::operator=
NRPROSProxy & operator=(const NRPROSProxy &)=delete
NRPROSProxy::publish
void publish(const std::string &address, const MSG_TYPE &msg, size_t queueSize=10)
Publishes 'msg' to ROS topic 'address'.
Definition: nrp_ros_proxy.h:62