Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00035 #include <ros/ros.h>
00036 #include <stdlib.h>
00037 #include <stdio.h>
00038 #include <unistd.h>
00039 #include <vector>
00040 #include <string>
00041 #include <signal.h>
00042 #include <boost/thread/mutex.hpp>
00043 #include <boost/thread/thread.hpp>
00044 #include <wifi_comm/WiFiNeighboursList.h>
00045 #include "std_msgs/String.h"
00046
00047 #include "wifi_comm/wifi_comm_lib.h"
00048
00049 using namespace wifi_comm;
00050
00051 WiFiComm * myComm;
00052 ros::NodeHandle * n;
00053
00054 std::vector<ros::Subscriber> subs;
00055
00056 void helloWorldCallback(std::string ip, const std_msgs::StringConstPtr& msg)
00057 {
00058 ROS_INFO("Received [%s] from %s", msg->data.c_str(), ip.c_str());
00059 }
00060
00061 void robotJoinedNetwork(char * ip)
00062 {
00063
00064 myComm->openForeignRelay(ip, "/wifi_hello_world", true);
00065
00066
00067 char topic[128];
00068 ros::Subscriber sub = n->subscribe<std_msgs::String>(WiFiComm::concatTopicAndIp(topic, "/wifi_hello_world", ip), 10, boost::bind(helloWorldCallback, std::string(ip), _1));
00069 subs.push_back(sub);
00070 }
00071
00072
00073
00074 int main( int argc, char** argv )
00075 {
00076 ros::init(argc, argv, "wifi_comm_example");
00077 n = new ros::NodeHandle();
00078
00079 myComm = new WiFiComm(robotJoinedNetwork);
00080
00081 ros::Publisher hello_world = n->advertise<std_msgs::String>("wifi_hello_world", 10);
00082
00083 ros::Rate r(0.5);
00084 while(ros::ok())
00085 {
00086 std_msgs::String msg;
00087 msg.data = "Hello World!";
00088 hello_world.publish(msg);
00089
00090 ros::spinOnce();
00091 r.sleep();
00092 }
00093
00094 delete myComm;
00095
00096 return 0;
00097 }
00098
00099
00100