Go to the documentation of this file.00001 #include <netinet/ip.h>
00002 #include <sys/ioctl.h>
00003 #include <net/if.h>
00004 #include <errno.h>
00005
00006 #include <string>
00007
00008 #include "ros/ros.h"
00009 #include "std_msgs/Bool.h"
00010
00011 static int socket_fd = -1;
00012
00013 bool initSocket()
00014 {
00015 socket_fd = socket( AF_INET, SOCK_DGRAM, 0 );
00016 if( socket_fd != -1 )
00017 return true;
00018 else
00019 return false;
00020 }
00021
00022 bool interfaceIsRunning( std::string interface_name )
00023 {
00024 struct ifreq ifr;
00025
00026 strcpy( ifr.ifr_name, interface_name.c_str() );
00027 if( ioctl( socket_fd, SIOCGIFFLAGS, &ifr ) < 0 )
00028 {
00029 static std::string last_warning;
00030 std::string warn = "Query of interface '" + interface_name + "' failed: '" + strerror( errno ) + "' Presuming down.";
00031
00032 const char * warning = warn.c_str();
00033 if( warning != last_warning )
00034 {
00035
00036 ROS_WARN("%s", warning);
00037 }
00038 last_warning = warning;
00039 return false;
00040 }
00041 bool running = (ifr.ifr_flags & IFF_RUNNING);
00042 bool up = (ifr.ifr_flags & IFF_UP);
00043
00044 return up && running;
00045 }
00046
00047 int main( int argc, char **argv )
00048 {
00049 ros::init( argc, argv, "network_detector" );
00050 ros::NodeHandle node;
00051 std::string interface_name;
00052 if( !ros::param::get( "~interface_name", interface_name ))
00053 {
00054 ROS_FATAL( "No parameter 'interface_name' specified. Don't know which interface to watch. Exiting." );
00055 exit(1);
00056 }
00057 ros::Publisher running_pub = node.advertise<std_msgs::Bool>( "network/connected", 0, true );
00058 int loop_count;
00059 bool first_time = true;
00060 bool was_running = false;
00061 float inner_loop_hertz = 4;
00062 ros::Rate loop_rate( inner_loop_hertz );
00063 if( !initSocket() )
00064 {
00065 ROS_FATAL( "Failed to open socket for network ioctl: '%s'. Exiting.",
00066 strerror( errno ));
00067 exit(1);
00068 }
00069 while( ros::ok() )
00070 {
00071 bool is_running = interfaceIsRunning( interface_name );
00072 if( is_running != was_running || first_time || loop_count > inner_loop_hertz * 5 )
00073 {
00074 if( is_running != was_running )
00075 {
00076 ROS_INFO( "Interface '%s' %s.", interface_name.c_str(), (is_running ? "connected" : "disconnected") );
00077 }
00078
00079 std_msgs::Bool msg;
00080 msg.data = is_running;
00081 running_pub.publish( msg );
00082
00083 loop_count = 0;
00084 first_time = false;
00085 }
00086 ros::spinOnce();
00087 loop_rate.sleep();
00088 loop_count++;
00089 was_running = is_running;
00090 }
00091 }