C++ class for the WiFiComm multi-robot communication lib. More...
#include <inc/wifi_comm_lib.h>
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< ForeignRelay > | foreign_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. |
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.
wifi_comm::WiFiComm::WiFiComm | ( | void(*)(char *ip) | fp | ) |
Deprecated constructor.
fp | C style callback function. |
Definition at line 39 of file wifi_comm_lib.cpp.
wifi_comm::WiFiComm::WiFiComm | ( | boost::function< void(char *ip)> | f | ) |
Destructor.
Definition at line 57 of file wifi_comm_lib.cpp.
void wifi_comm::WiFiComm::closeForeignRelay | ( | char * | ip | ) | [private] |
Close foreign relay.
This function closes an existing foreign relay.
ip | The 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.
final_topic | C-string containing the final topic. |
topic | C-string containing the base topic name. |
ip | C-string containing the ip adress. |
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.
msg | Received 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.
ip | C-string containing the ip adress. |
topic | C-string containing the topic name. |
public_publish | Wether to publish an ip specific topic or not. |
append_my_ip | Wether to append my ip to the topic on the receiving end or not |
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.
ip | C-string containing the ip adress. |
topic | C-string containing the local topic name. |
topic | C-string containing the foreign topic name. |
Definition at line 115 of file wifi_comm_lib.cpp.
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.
std::vector<ForeignRelay> wifi_comm::WiFiComm::foreign_relays_ [private] |
Vector of foreign relays.
Definition at line 135 of file wifi_comm_lib.h.
ros::NodeHandle wifi_comm::WiFiComm::n_ [private] |
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.
bool wifi_comm::WiFiComm::using_boost_ [private] |
Whether we are using the boost callback function or not.
Definition at line 156 of file wifi_comm_lib.h.