2 #ifndef _TRANSPORT_ROSBRIDGEREADTHREAD_H_
3 #define _TRANSPORT_ROSBRIDGEREADTHREAD_H_
7 #include "madara/threads/BaseThread.h"
12 #pragma GCC diagnostic push
13 #pragma GCC diagnostic ignored "-Wpedantic"
14 #pragma GCC diagnostic ignored "-Wreorder"
18 #include "std_msgs/String.h"
19 #include "topic_tools/shape_shifter.h"
22 #pragma GCC diagnostic pop
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);
56 virtual void init(madara::knowledge::KnowledgeBase & knowledge);
61 virtual void run(
void);
64 const std::string &topic_name );
70 madara::knowledge::ThreadSafeContext *
context_;
73 const std::string
id_;
79 madara::utility::ScopedArray <char>
buffer_;
A custom read thread generated by gpc.pl.
unsigned int message_count_
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
unsigned int message_count()
madara::transport::QoSTransportSettings settings_
the transport settings being used
std::vector< std::string > topics_
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.