bridge_node.hpp
Go to the documentation of this file.
1 
18 #ifndef __BRIDGE_NODE__
19 #define __BRIDGE_NODE__
20 #include <ros/ros.h>
21 #include <stdio.h>
22 #include <stdlib.h>
23 #include <thread>
24 #include <iostream>
25 #include <unistd.h>
26 #include <string>
27 #include <zmqpp/zmqpp.hpp>
28 /*
29 zmqpp is the c++ wrapper around ZeroMQ
30 Intall zmqpp first:
31  sudo apt install libzmqpp-dev
32 zmqpp reference link:
33  https://zeromq.github.io/zmqpp/namespacezmqpp.html
34 */
35 #include "ros_sub_pub.hpp"
36 
37 struct TopicInfo
38 {
39  std::string name;
40  std::string type;
41  int max_freq;
42  std::string ip;
43  int port;
44 };
45 
46 //********************* Parse configuration file **************************
47 std::string ns; // namespace of this node
51 int len_send; // length(number) of send topics
52 int len_recv; // length(number) of receive topics
53 
54 std::map<std::string, std::string> ip_map; // map host name and IP
55 
56 std::vector<TopicInfo> sendTopics; // send topics info struct vector
57 std::vector<TopicInfo> recvTopics; // receive topics info struct vector
58 
59 // ********************* zmq socket initialize ***************************
60 zmqpp::context_t context;
61 std::vector<std::unique_ptr<zmqpp::socket>> senders; //index senders
62 std::vector<std::unique_ptr<zmqpp::socket>> receivers; //index receivers
63 
64 // ******************* ROS subscribe and publish *************************
65 std::vector<ros::Subscriber> topic_subs;
66 std::vector<ros::Publisher> topic_pubs;
67 
68 // ******************* send frequency control ***************************
69 std::vector<ros::Time> sub_t_last;
70 std::vector<int> send_num;
71 bool send_freq_control(int i);
72 
73 // ****************** launch receive threads *****************************
74 std::vector<bool> recv_thread_flags;
75 std::vector<bool> recv_flags_last;
76 std::vector<std::thread> recv_threads;
77 void recv_func(int i);
78 
79 // ***************** stop send/receive ******************************
80 void stop_send(int i);
81 void stop_recv(int i);
82 
83 #endif
std::vector< std::unique_ptr< zmqpp::socket > > senders
Definition: bridge_node.hpp:61
std::vector< TopicInfo > recvTopics
Definition: bridge_node.hpp:57
int len_send
Definition: bridge_node.hpp:51
int len_recv
Definition: bridge_node.hpp:52
std::vector< ros::Subscriber > topic_subs
Definition: bridge_node.hpp:65
std::vector< std::unique_ptr< zmqpp::socket > > receivers
Definition: bridge_node.hpp:62
void stop_recv(int i)
std::vector< int > send_num
Definition: bridge_node.hpp:70
XmlRpc::XmlRpcValue recv_topics_xml
Definition: bridge_node.hpp:50
XmlRpc::XmlRpcValue ip_xml
Definition: bridge_node.hpp:48
void stop_send(int i)
void recv_func(int i)
std::vector< ros::Publisher > topic_pubs
Definition: bridge_node.hpp:66
std::string name
Definition: bridge_node.hpp:39
XmlRpc::XmlRpcValue send_topics_xml
Definition: bridge_node.hpp:49
Header file for different ROS message type.
std::vector< ros::Time > sub_t_last
Definition: bridge_node.hpp:69
std::string ip
Definition: bridge_node.hpp:42
std::string ns
Definition: bridge_node.hpp:47
std::vector< bool > recv_flags_last
Definition: bridge_node.hpp:75
zmqpp::context_t context
Definition: bridge_node.hpp:60
bool send_freq_control(int i)
Definition: bridge_node.cpp:43
std::map< std::string, std::string > ip_map
Definition: bridge_node.hpp:54
std::string type
Definition: bridge_node.hpp:40
std::vector< bool > recv_thread_flags
Definition: bridge_node.hpp:74
std::vector< TopicInfo > sendTopics
Definition: bridge_node.hpp:56
std::vector< std::thread > recv_threads
Definition: bridge_node.hpp:76


swarm_ros_bridge
Author(s):
autogenerated on Tue Feb 21 2023 03:43:52