Custom network transport generated by gpc.pl.
More...
#include <RosBridge.h>
|
| RosBridge (const std::string &id, madara::transport::TransportSettings &new_settings, madara::knowledge::KnowledgeBase &context, std::vector< std::string > topics, std::map< std::string, std::string > topic_map, std::map< std::string, std::string > pub_topic_types) |
| Constructor. More...
|
|
virtual | ~RosBridge () |
| Destructor. More...
|
|
unsigned int | in_message_count () |
|
unsigned int | out_message_count () |
|
long | send_data (const madara::knowledge::KnowledgeMap &modifieds) |
| Sends a list of updates to the domain. More...
|
|
Custom network transport generated by gpc.pl.
Definition at line 17 of file RosBridge.h.
◆ RosBridge()
gams::transports::RosBridge::RosBridge |
( |
const std::string & |
id, |
|
|
madara::transport::TransportSettings & |
new_settings, |
|
|
madara::knowledge::KnowledgeBase & |
context, |
|
|
std::vector< std::string > |
topics, |
|
|
std::map< std::string, std::string > |
topic_map, |
|
|
std::map< std::string, std::string > |
pub_topic_types |
|
) |
| |
Constructor.
- Parameters
-
id | unique identifier(generally host:port) |
new_settings | settings to apply to the transport |
context | the knowledge record context |
topics | vector of topics to subscribe |
topic_map | map from ros topic name to madara var name |
pub_topic_types | map from ros topic name to ros topic type |
◆ ~RosBridge()
virtual gams::transports::RosBridge::~RosBridge |
( |
| ) |
|
|
virtual |
◆ get_update_container_pair_()
std::pair<std::string, std::string> gams::transports::RosBridge::get_update_container_pair_ |
( |
const char * |
container_name | ) |
|
|
protected |
◆ in_message_count()
unsigned int gams::transports::RosBridge::in_message_count |
( |
| ) |
|
◆ out_message_count()
unsigned int gams::transports::RosBridge::out_message_count |
( |
| ) |
|
◆ send_data()
long gams::transports::RosBridge::send_data |
( |
const madara::knowledge::KnowledgeMap & |
modifieds | ) |
|
Sends a list of updates to the domain.
This function must be implemented by your transport
- Parameters
-
modifieds | a list of keys to values of all records that have been updated and could be sent. |
- Returns
- result of operation or -1 if we are shutting down
◆ message_count_
unsigned int gams::transports::RosBridge::message_count_ |
|
protected |
◆ parser_
◆ pub_topic_types_
std::map<std::string, std::string> gams::transports::RosBridge::pub_topic_types_ |
|
protected |
◆ read_thread_
◆ read_threads_
madara::threads::Threader gams::transports::RosBridge::read_threads_ |
|
protected |
threads for monitoring knowledge updates
Definition at line 55 of file RosBridge.h.
◆ topic_map_
std::map<std::string, std::string> gams::transports::RosBridge::topic_map_ |
|
protected |
◆ topics_
std::vector<std::string> gams::transports::RosBridge::topics_ |
|
protected |
The documentation for this class was generated from the following file: