1 #include <netinet/ip.h> 9 #include "std_msgs/Bool.h" 15 socket_fd = socket( AF_INET, SOCK_DGRAM, 0 );
26 strcpy( ifr.ifr_name, interface_name.c_str() );
27 if( ioctl(
socket_fd, SIOCGIFFLAGS, &ifr ) < 0 )
29 static std::string last_warning;
30 std::string warning =
"Query of interface '" + interface_name +
"' failed: '" + strerror( errno ) +
"' Presuming down.";
31 if( warning != last_warning )
35 last_warning = warning;
38 bool running = (ifr.ifr_flags & IFF_RUNNING);
39 bool up = (ifr.ifr_flags & IFF_UP);
44 int main(
int argc,
char **argv )
46 ros::init( argc, argv,
"network_detector" );
48 std::string interface_name;
51 ROS_FATAL(
"No parameter 'interface_name' specified. Don't know which interface to watch. Exiting." );
56 bool first_time =
true;
57 bool was_running =
false;
58 float inner_loop_hertz = 4;
62 ROS_FATAL(
"Failed to open socket for network ioctl: '%s'. Exiting.",
69 if( is_running != was_running || first_time || loop_count > inner_loop_hertz * 5 )
71 if( is_running != was_running )
73 ROS_INFO(
"Interface '%s' %s.", interface_name.c_str(), (is_running ?
"connected" :
"disconnected") );
77 msg.data = is_running;
86 was_running = is_running;
void publish(const boost::shared_ptr< M > &message) const
ROSCPP_DECL void init(int &argc, char **argv, const std::string &name, uint32_t options=0)
ROSCPP_DECL bool get(const std::string &key, std::string &s)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
bool interfaceIsRunning(std::string interface_name)
ROSCPP_DECL void spinOnce()
int main(int argc, char **argv)