GAMS  1.4.0
RosBridgeReadThread.h
Go to the documentation of this file.
1 
2 #ifndef _TRANSPORT_ROSBRIDGEREADTHREAD_H_
3 #define _TRANSPORT_ROSBRIDGEREADTHREAD_H_
4 
5 #include <string>
6 
7 #include "madara/threads/BaseThread.h"
9 
10 // ROS includes
11 #ifdef __GNUC__
12 #pragma GCC diagnostic push
13 #pragma GCC diagnostic ignored "-Wpedantic"
14 #pragma GCC diagnostic ignored "-Wreorder"
15 #endif
16 
17 #include "ros/ros.h"
18 #include "std_msgs/String.h"
19 #include "topic_tools/shape_shifter.h"
20 
21 #ifdef __GNUC__
22 #pragma GCC diagnostic pop
23 #endif
24 
25 namespace gams
26 {
27  namespace transports
28  {
32  class RosBridgeReadThread : public madara::threads::BaseThread
33  {
34  public:
39  const std::string & id,
40  const madara::transport::TransportSettings & settings,
41  madara::transport::BandwidthMonitor & send_monitor,
42  madara::transport::BandwidthMonitor & receive_monitor,
43  madara::transport::PacketScheduler & packet_scheduler,
44  std::vector<std::string> topics,
45  std::map<std::string,std::string> topic_map);
46 
51 
56  virtual void init(madara::knowledge::KnowledgeBase & knowledge);
57 
61  virtual void run(void);
62 
63  void messageCallback(const topic_tools::ShapeShifter::ConstPtr& msg,
64  const std::string &topic_name );
65 
66  unsigned int message_count();
67 
68  private:
70  madara::knowledge::ThreadSafeContext * context_;
71 
73  const std::string id_;
74 
76  madara::transport::QoSTransportSettings settings_;
77 
79  madara::utility::ScopedArray <char> buffer_;
80 
82  madara::knowledge::CompiledExpression on_data_received_;
83 
85  madara::transport::BandwidthMonitor & send_monitor_;
86 
88  madara::transport::BandwidthMonitor & receive_monitor_;
89 
91  madara::transport::PacketScheduler & packet_scheduler_;
92 
93  std::vector<ros::Subscriber> subscribers_;
94 
95  gams::utility::ros::RosParser * parser_;
96 
97  // Enabled topics
98  std::vector<std::string> topics_;
99  // Topic map
100  std::map<std::string,std::string> topic_map_;
101 
102  unsigned int message_count_;
103 
104  };
105  }
106 } // end namespace threads
107 
108 #endif // _TRANSPORT_ROSBRIDGEREADTHREAD_H_
A custom read thread generated by gpc.pl.
madara::knowledge::ThreadSafeContext * context_
data plane if we want to access the knowledge base
gams::utility::ros::RosParser * parser_
void messageCallback(const topic_tools::ShapeShifter::ConstPtr &msg, const std::string &topic_name)
virtual void run(void)
Executes the main thread logic.
madara::transport::BandwidthMonitor & receive_monitor_
monitor the bandwidth used by others
const std::string id_
the unique id of this agent(probably a host:port pairing)
std::map< std::string, std::string > topic_map_
madara::transport::BandwidthMonitor & send_monitor_
monitor the bandwidth used for sending
madara::transport::QoSTransportSettings settings_
the transport settings being used
std::vector< ros::Subscriber > subscribers_
madara::utility::ScopedArray< char > buffer_
buffer for sending
virtual ~RosBridgeReadThread()
Destructor.
virtual void init(madara::knowledge::KnowledgeBase &knowledge)
Initializes thread with MADARA context.
madara::knowledge::CompiledExpression on_data_received_
data received rules, defined in Transport settings
madara::transport::PacketScheduler & packet_scheduler_
a specialty packet scheduler for experimental drop policies
RosBridgeReadThread(const std::string &id, const madara::transport::TransportSettings &settings, madara::transport::BandwidthMonitor &send_monitor, madara::transport::BandwidthMonitor &receive_monitor, madara::transport::PacketScheduler &packet_scheduler, std::vector< std::string > topics, std::map< std::string, std::string > topic_map)
Default constructor.
Contains all GAMS-related tools, classes and code.