find_camera.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2008, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of the Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <ros/console.h>
36 #include <sys/types.h>
37 #include <sys/socket.h>
38 #include <ifaddrs.h>
39 #include <netinet/ip.h>
40 #include <netinet/in.h>
41 #include <arpa/inet.h>
42 #include <errno.h>
43 #include <string.h>
44 
46 {
47  int insock;
48  struct sockaddr_in recvaddr;
49 
50  if ((insock = socket(PF_INET,SOCK_DGRAM,0)) == -1)
51  {
52  ROS_ERROR("Error opening input socket.");
53  return -1;
54  }
55 
56  // Address to receive at.
57  memset(&recvaddr, 0, sizeof(recvaddr));
58  recvaddr.sin_family = AF_INET;
59  recvaddr.sin_addr.s_addr = INADDR_BROADCAST;
60  recvaddr.sin_port = htons(1234);
61 
62  if (bind(insock, (struct sockaddr*) &recvaddr, sizeof recvaddr) == -1)
63  {
64  ROS_ERROR("Can't bind to socket to receive.");
65  close(insock);
66  return -1;
67  }
68 
69  return insock;
70 }
71 
72 int send_query(struct ifaddrs *iface, int srcport)
73 {
74  int outsock;
75  int port = 3956;
76  int broadcast=1;
77  struct sockaddr_in sendaddr;
78  struct sockaddr_in recvaddr;
79 
80  if ((outsock = socket(PF_INET,SOCK_DGRAM,0)) == -1)
81  {
82  ROS_ERROR("Error opening output socket.");
83  return -1;
84  }
85 
86  // Address to receive at.
87  memset(&sendaddr, 0, sizeof(sendaddr));
88  sendaddr.sin_family = AF_INET;
89  sendaddr.sin_addr.s_addr = ((sockaddr_in *) iface->ifa_addr)->sin_addr.s_addr;
90  sendaddr.sin_port = htons(srcport);
91 
92  if (bind(outsock, (struct sockaddr*) &sendaddr, sizeof sendaddr) == -1)
93  {
94  ROS_ERROR("Can't bind to socket on interface %s.", iface->ifa_name);
95  close(outsock);
96  return -1;
97  }
98 
99  // Send a broadcast.
100  if ((setsockopt(outsock,SOL_SOCKET,SO_BROADCAST, &broadcast,sizeof broadcast)) == -1)
101  {
102  ROS_ERROR("Can't set broadcast flag on interface %s.", iface->ifa_name);
103  close(outsock);
104  return -1;
105  }
106 
107  memset(&recvaddr, 0, sizeof(recvaddr));
108  recvaddr.sin_family = AF_INET;
109  recvaddr.sin_port = htons(port);
110  recvaddr.sin_addr.s_addr = INADDR_BROADCAST;
111 
112  char outpkt[] = { 0x42, 0x11, 0x00, 0x02, 0x00, 0x00, 0x06, 0x26 };
113 
114  if (sendto(outsock, outpkt, sizeof(outpkt) , 0, (struct sockaddr *)&recvaddr, sizeof(recvaddr)) != sizeof(outpkt))
115  {
116  ROS_ERROR("Failed sending packet on interface %s.", iface->ifa_name);
117  close(outsock);
118  return -1;
119  }
120 
121  close(outsock);
122  return 0;
123 }
124 
125 void get_response(int fd)
126 {
127  ROS_INFO("Got a response on socket %i.", fd);
128 }
129 
130 int collect_replies(fd_set *master_set, int maxfd)
131 {
132  struct timeval tv;
133  int retval;
134  fd_set tmpset;
135 
136  tv.tv_sec = 1;
137  tv.tv_usec = 0;
138 
139  while (1)
140  {
141  memcpy(&tmpset, master_set, sizeof(tmpset));
142  retval = select(maxfd + 1, &tmpset, NULL, NULL, &tv);
143 
144  if (retval < 0 && errno != EINTR)
145  {
146  ROS_ERROR("Select exited with an error code.");
147  return -1;
148  }
149 
150  if (!retval)
151  return 0;
152 
153  ROS_INFO("Got packet %i.", retval);
154  for (int i = 0; i <= maxfd && retval > 0; i++)
155  if (FD_ISSET(i, &tmpset))
156  {
157  get_response(i);
158  retval--;
159  }
160  }
161 }
162 
163 int get_local_port(int fd)
164 {
165  struct sockaddr localPort;
166  socklen_t localPortLen;
167 
168  if (getsockname(fd, &localPort, &localPortLen) == -1)
169  {
170  ROS_ERROR("Unable to get local port for socket.");
171  return -1;
172  }
173 
174  return ntohs(((struct sockaddr_in *)&localPort)->sin_port);
175 }
176 
177 int main()
178 {
179  struct ifaddrs *ifaces = NULL;
180  fd_set fdset;
181  int maxfd = 0;
182 
183  if (getifaddrs(&ifaces))
184  {
185  ROS_ERROR("Couldn't get interface list.");
186  return 1;
187  }
188 
189  FD_ZERO(&fdset);
190  maxfd = receive_socket();
191  if (maxfd < 0)
192  return 1;
193  FD_SET(maxfd, &fdset);
194 
195  int port = get_local_port(maxfd);
196 
197  for (struct ifaddrs *curif = ifaces; curif; curif = curif->ifa_next)
198  {
199  if (curif->ifa_addr && curif->ifa_addr->sa_family == AF_INET)
200  send_query(curif, port);
201  }
202 
203  freeifaddrs(ifaces);
204 
205  return collect_replies(&fdset, maxfd) != 0;
206 }
int main()
int get_local_port(int fd)
void get_response(int fd)
#define ROS_INFO(...)
int collect_replies(fd_set *master_set, int maxfd)
int receive_socket()
Definition: find_camera.cpp:45
int send_query(struct ifaddrs *iface, int srcport)
Definition: find_camera.cpp:72
#define ROS_ERROR(...)


prosilica_camera
Author(s): Maintained by William Woodall - wwoodall@willowgarage.com, Contributions by Allison Thackston - allison.thackston@nasa.gov
autogenerated on Mon Jun 10 2019 14:20:19