Public Member Functions | Static Public Member Functions | Public Attributes | Private Member Functions | Private Attributes
wifi_comm::WiFiComm Class Reference

C++ class for the WiFiComm multi-robot communication lib. More...

#include <inc/wifi_comm_lib.h>

List of all members.

Public Member Functions

std::string * openForeignRelay (char *ip, char *topic, bool public_publish=true, bool append_my_ip=true)
 Open foreign relay.
std::string * openForeignRelay (char *ip, char *local_topic, char *foreign_topic)
 Open foreign relay.
 WiFiComm (void(*fp)(char *ip))
 Deprecated constructor.
 WiFiComm (boost::function< void(char *ip)> f)
 Constructor.
 ~WiFiComm ()
 Destructor.

Static Public Member Functions

static char * concatTopicAndIp (char *final_topic, char *topic, const char *ip)
 Concat topic and ip.

Public Attributes

wifi_comm::WiFiNeighboursList neighbours_list_
 List of neighbour robots.

Private Member Functions

void closeForeignRelay (char *ip)
 Close foreign relay.
void neighboursListUpdated (const wifi_comm::WiFiNeighboursListConstPtr &msg)
 Goal callback.

Private Attributes

boost::function< void(char *) boost_callback_ )
 Boost callback function.
void(* c_callback_ )(char *ip)
 C style callback function.
std::vector< ForeignRelayforeign_relays_
 Vector of foreign relays.
ros::NodeHandle n_
 Node handle.
ros::Subscriber neighbours_sub_
 Subscriber for the WiFiNeighboursList message.
bool using_boost_
 Whether we are using the boost callback function or not.

Detailed Description

C++ class for the WiFiComm multi-robot communication lib.

This class allows for multi-robot communication through the use of OLSRD and the WifiComm discovery node.

Definition at line 68 of file wifi_comm_lib.h.


Constructor & Destructor Documentation

wifi_comm::WiFiComm::WiFiComm ( void(*)(char *ip)  fp)

Deprecated constructor.

Parameters:
fpC style callback function.

Definition at line 39 of file wifi_comm_lib.cpp.

wifi_comm::WiFiComm::WiFiComm ( boost::function< void(char *ip)>  f)

Constructor.

Parameters:
fBoost callback function.

Definition at line 49 of file wifi_comm_lib.cpp.

Destructor.

Definition at line 57 of file wifi_comm_lib.cpp.


Member Function Documentation

void wifi_comm::WiFiComm::closeForeignRelay ( char *  ip) [private]

Close foreign relay.

This function closes an existing foreign relay.

Parameters:
ipThe ip adress of the foreign relays to close.

Definition at line 145 of file wifi_comm_lib.cpp.

char * wifi_comm::WiFiComm::concatTopicAndIp ( char *  final_topic,
char *  topic,
const char *  ip 
) [static]

Concat topic and ip.

This function concatenates a topic and an ip adress thus creating a unique topic to be advertised.

Parameters:
final_topicC-string containing the final topic.
topicC-string containing the base topic name.
ipC-string containing the ip adress.
Returns:
A pointer to the final topic.

Definition at line 66 of file wifi_comm_lib.cpp.

void wifi_comm::WiFiComm::neighboursListUpdated ( const wifi_comm::WiFiNeighboursListConstPtr &  msg) [private]

Goal callback.

This function is a callback for receiving WiFiNeighboursList messages.

Parameters:
msgReceived WiFiNeighboursList message.

Definition at line 180 of file wifi_comm_lib.cpp.

std::string * wifi_comm::WiFiComm::openForeignRelay ( char *  ip,
char *  topic,
bool  public_publish = true,
bool  append_my_ip = true 
)

Open foreign relay.

This function opens a foreign relay to publish a local topic on a foreign roscore at the given ip adress.

Parameters:
ipC-string containing the ip adress.
topicC-string containing the topic name.
public_publishWether to publish an ip specific topic or not.
append_my_ipWether to append my ip to the topic on the receiving end or not
Returns:
Foreign roscore ip adress.

Definition at line 77 of file wifi_comm_lib.cpp.

std::string * wifi_comm::WiFiComm::openForeignRelay ( char *  ip,
char *  local_topic,
char *  foreign_topic 
)

Open foreign relay.

This function opens a foreign relay to publish a local topic on a foreign roscore at the given ip adress.

Parameters:
ipC-string containing the ip adress.
topicC-string containing the local topic name.
topicC-string containing the foreign topic name.
Returns:
Foreign roscore ip adress.

Definition at line 115 of file wifi_comm_lib.cpp.


Member Data Documentation

boost::function<void(char*) wifi_comm::WiFiComm::boost_callback_) [private]

Boost callback function.

Definition at line 160 of file wifi_comm_lib.h.

void(* wifi_comm::WiFiComm::c_callback_)(char *ip) [private]

C style callback function.

Definition at line 158 of file wifi_comm_lib.h.

Vector of foreign relays.

Definition at line 135 of file wifi_comm_lib.h.

Node handle.

Definition at line 130 of file wifi_comm_lib.h.

wifi_comm::WiFiNeighboursList wifi_comm::WiFiComm::neighbours_list_

List of neighbour robots.

Definition at line 126 of file wifi_comm_lib.h.

Subscriber for the WiFiNeighboursList message.

Definition at line 132 of file wifi_comm_lib.h.

Whether we are using the boost callback function or not.

Definition at line 156 of file wifi_comm_lib.h.


The documentation for this class was generated from the following files:


wifi_comm
Author(s): Gonçalo Cabrita and Pedro Sousa
autogenerated on Mon Jan 6 2014 11:27:05