wge100lib.c
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, 2010 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 
36 #include <stdio.h>
37 #include <stdlib.h>
38 #include <string.h>
39 #include <sys/time.h>
40 #include <errno.h>
41 #include <unistd.h>
42 #include <stdbool.h>
43 #include <net/if.h>
44 #include <ifaddrs.h>
45 
48 
50 #define STD_REPLY_TIMEOUT SEC_TO_USEC(0.2) // Should be tens of ms at least or flash writes will fail.
51 #define STOP_REPLY_TIMEOUT SEC_TO_USEC(0.001)
52 
60  return WGE100LIB_VERSION;
61 }
62 
63 
94 int wge100FindByUrl(const char *url, IpCamList *camera, unsigned wait_us, const char **errmsg)
95 {
96  static const char *badprefix = "Bad URL prefix, expected name://, serial:// or any://.";
97  static const char *multiaddress = "Multiple @-prefixed camera addresses found.";
98  static const char *multiinterface = "Multiple #-prefixed host interfaces found.";
99  static const char *discoverfailed = "Discover failed. The specified address or interface may be bad.";
100  static const char *badserial = "serial:// may only be followed by an integer.";
101  static const char *badany = "Unexpected characters after any://.";
102  static const char *badip = "@ must be followed by a valid IP address.";
103  static const char *nomatch = "No cameras matched the URL.";
104  static const char *multimatch = "More than one camera matched the URL.";
105  static const char *illegalcase = "Illegal case, this is a bug.";
106  static const char *nomem = "malloc failed";
107  const char *name = "name://"; int namelen = strlen(name);
108  const char *serial = "serial://"; int seriallen = strlen(serial);
109  const char *any = "any://"; int anylen = strlen(any);
110  char *idstart;
111  char *curpos;
112  char *address = NULL;
113  char *interface = NULL;
114  char *copy = malloc(strlen(url) + 1);
115  int retval = -1;
116  int camcount = 0;
117  int mode = 0;
118  unsigned int serialnum = -1;
119  IpCamList camList;
120  IpCamList *curEntry;
121 
122  wge100CamListInit(&camList); // Must happen before any potential failures.
123 
124  if (errmsg)
125  *errmsg = illegalcase; // If we return an error
126 
127  if (!copy) // malloc is above.
128  {
129  *errmsg = nomem;
130  return -1;
131  }
132  strcpy(copy, url);
133 
134  // Decypher the prefix.
135  if (!strncmp(copy, name, namelen))
136  {
137  idstart = copy + namelen;
138  mode = 1;
139  }
140  else if (!strncmp(copy, serial, seriallen))
141  {
142  idstart = copy + seriallen;
143  mode = 2;
144  }
145  else if (!strncmp(copy, any, anylen))
146  {
147  idstart = copy + anylen;
148  mode = 3;
149  }
150  else
151  {
152  if (errmsg)
153  *errmsg = badprefix;
154  goto bailout;
155  }
156 
157  // Find any # or @ words.
158  for (curpos = idstart; *curpos; curpos++)
159  {
160  if (*curpos == '@')
161  {
162  if (address)
163  {
164  if (errmsg)
165  *errmsg = multiaddress;
166  goto bailout;
167  }
168  address = curpos + 1;
169  }
170  else if (*curpos == '#')
171  {
172  if (interface)
173  {
174  if (errmsg)
175  *errmsg = multiinterface;
176  goto bailout;
177  }
178  interface = curpos + 1;
179  }
180  else
181  continue; // Didn't find anything, don't terminate the string.
182  *curpos = 0;
183  }
184  // Now idstart, address and interface are set.
185 
186  if (mode == 3 && *idstart)
187  {
188  if (errmsg)
189  *errmsg = badany;
190  goto bailout;
191  }
192 
193  if (mode == 2) // serial:// convert the number to integer.
194  {
195  char *endpos;
196  serialnum = strtol(idstart, &endpos, 10);
197  if (*idstart == 0 || *endpos != 0)
198  {
199  if (errmsg)
200  *errmsg = badserial;
201  goto bailout;
202  }
203  }
204 
205  // Build up a list of cameras. Only ones that are on the specified
206  // interface (if specified), and that can reply from the specified
207  // address (if specified) will end up in the list.
208  if (wge100Discover(interface, &camList, address, wait_us) == -1)
209  {
210  if (errmsg)
211  *errmsg = discoverfailed;
212  goto bailout;
213  }
214 
215  // Now search through the list for a match.
216  camcount = 0;
217  list_for_each_entry(curEntry, &(camList.list), list)
218  {
219  if ((mode == 1 && strcmp(idstart, curEntry->cam_name) == 0) ||
220  (mode == 2 && serialnum == curEntry->serial) ||
221  mode == 3)
222  {
223  camcount++;
224  if (camcount > 1)
225  {
226  if (errmsg)
227  *errmsg = multimatch;
228  goto bailout;
229  }
230  memcpy(camera, curEntry, sizeof(IpCamList));
231  if (address) // If an address has been specified, we fill it into the camera info.
232  {
233  struct in_addr ip;
234  if (inet_aton(address, &ip))
235  {
236  uint8_t *ipbytes = (uint8_t *) &ip.s_addr; // Reconstruct the address, we don't want any funny stuff with the user-provided string.
237  snprintf(camera->ip_str, sizeof(camera->ip_str), "%i.%i.%i.%i", ipbytes[0], ipbytes[1], ipbytes[2], ipbytes[3]);
238  camera->ip = ip.s_addr;
239  }
240  else
241  {
242  if (errmsg)
243  *errmsg = badip;
244  goto bailout;
245  }
246  }
247  }
248  }
249 
250  switch (camcount)
251  {
252  case 1: // Found exactly one camera, we're good!
253  retval = 0;
254  break;
255 
256  case 0: // Found no cameras
257  if (errmsg)
258  *errmsg = nomatch;
259  break;
260 
261  default:
262  if (errmsg)
263  *errmsg = illegalcase;
264  break;
265  }
266 
267 bailout:
268  wge100CamListDelAll(&camList);
269  free(copy);
270  return retval;
271 }
272 
287 int wge100StatusWait( int s, uint32_t wait_us, uint32_t *type, uint32_t *code ) {
288  if( wge100WaitForPacket(&s, 1, PKTT_STATUS, sizeof(PacketStatus), &wait_us) != -1 && (wait_us != 0) ) {
289  PacketStatus sPkt;
290  if( recvfrom( s, &sPkt, sizeof(PacketStatus), 0, NULL, NULL ) == -1 ) {
291  perror("wge100StatusWait unable to receive from socket");
292  *type = PKT_STATUST_ERROR;
293  *code = PKT_ERROR_SYSERR;
294  return -1;
295  }
296 
297  *type = ntohl(sPkt.status_type);
298  *code = ntohl(sPkt.status_code);
299  return 0;
300  }
301 
302  *type = PKT_STATUST_ERROR;
303  *code = PKT_ERROR_TIMEOUT;
304  return 0;
305 }
306 
307 
308 static void xormem(uint8_t *dst, uint8_t *src, size_t w)
309 {
310  while (w--)
311  *dst++ ^= *src++;
312 }
313 
314 static int wge100DiscoverSend(const char *ifName, const char *ipAddress)
315 {
316  // Create and initialize a new Discover packet
317  PacketDiscover dPkt;
318  dPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
319  dPkt.hdr.type = htonl(PKTT_DISCOVER);
320  strncpy(dPkt.hdr.hrt, "DISCOVER", sizeof(dPkt.hdr.hrt));
321 
322  /* Create a new socket bound to a local ephemeral port, and get our local connection
323  * info so we can request a reply back to the same socket.
324  */
325  int s = wge100CmdSocketCreate(ifName, &dPkt.hdr.reply_to);
326  if(s == -1) {
327  //perror("Unable to create socket\n");
328  return -1;
329  }
330 
333 
334  struct in_addr newIP;
335  if (ipAddress) // An IP was specified
336  {
337  inet_aton(ipAddress, &newIP);
338  dPkt.ip_addr = newIP.s_addr;
339  }
340  else
341  {
342  struct in_addr localip;
343  struct in_addr netmask;
344  wge100IpGetLocalAddr(ifName, &localip);
345  wge100IpGetLocalNetmask(ifName, &netmask);
346  dPkt.ip_addr = localip.s_addr ^ netmask.s_addr ^ ~0;
347  }
348 
349  if( wge100SendUDPBcast(s, ifName, &dPkt,sizeof(dPkt)) == -1) {
350  perror("Unable to send broadcast\n");
351  }
352 
353  /*// For the old API
354  if( wge100SendUDPBcast(s, ifName, &dPkt,sizeof(dPkt)-sizeof(dPkt.ip_addr)) == -1) {
355  perror("Unable to send broadcast\n");
356  }*/
357 
358  return s;
359 }
360 
372 int wge100Discover(const char *ifName, IpCamList *ipCamList, const char *ipAddress, unsigned wait_us) {
373  int retval = -1;
374  int *s = NULL; // Sockets to receive from
375  int numif = 1;
376  int nums = 0; // Number of sockets to receive from
377  int i;
378  const char **ifNames = NULL;
379  struct ifaddrs *ifaces = NULL;
380  struct ifaddrs *curif;
381  int autoif = 0;
382 
383  // Count the number of new cameras found
384  int newCamCount = 0;
385 
386  if (!ifName || !ifName[0]) // The interface has been specified.
387  {
388  autoif = 1;
389  if (getifaddrs(&ifaces))
390  {
391  perror("getifaddrs failed");
392  goto err;
393  }
394 
395  numif = 0;
396  for (curif = ifaces; curif; curif = curif->ifa_next)
397  numif++;
398  //fprintf(stderr, "There are %i interfaces.\n", numif);
399  }
400 
401  ifNames = calloc(numif, sizeof(char *));
402  if (!ifNames)
403  {
404  perror("allocating interfaces memory");
405  goto err; // Okay because nums == 0 and s and ifNames are allocated or NULL.
406  }
407 
408  if (!autoif)
409  ifNames[0] = ifName;
410  else
411  {
412  for (numif = 0, curif = ifaces; curif; curif = curif->ifa_next)
413  {
414  //fprintf(stderr, "Adding %s to discover list.\n", curif->ifa_name);
415  if (curif->ifa_addr && curif->ifa_addr->sa_family == AF_INET)
416  ifNames[numif++] = curif->ifa_name;
417  }
418  }
419 
420  s = calloc(numif, sizeof(int));
421  if (!s)
422  {
423  perror("allocating socket memory");
424  goto err; // Okay because nums == 0 and s and ifNames are allocated or NULL.
425  }
426 
427  for (nums = 0; nums < numif; nums++)
428  {
429  s[nums] = wge100DiscoverSend(ifNames[nums], ipAddress);
430  if (s[nums] == -1)
431  {
432  //fprintf(stderr, "Removing interface %s.\n", ifNames[nums]);
433  // Delete this interface as discovery has failed on it.
434  numif--;
435  for (i = nums; i < numif; i++)
436  {
437  ifNames[i] = ifNames[i+1];
438  }
439  nums--;
440  }
441  }
442 
443  do {
444  // Wait in the loop for replies. wait_us is updated each time through the loop.
445  int curs = wge100WaitForPacket(s, nums, PKTT_ANNOUNCE, sizeof(PacketAnnounce) - CAMERA_NAME_LEN - sizeof(IPAddress), &wait_us);
446  if( curs != -1 && wait_us != 0 ) {
447  // We've received an Announce packet, so pull it out of the receive queue
448  PacketAnnounce aPkt;
449  struct sockaddr_in fromaddr;
450  fromaddr.sin_family = AF_INET;
451  socklen_t fromlen = sizeof(fromaddr);
452  ssize_t packet_len;
453 
454  packet_len = recvfrom( s[curs], &aPkt, sizeof(PacketAnnounce), 0, (struct sockaddr *) &fromaddr, &fromlen);
455  if(packet_len == -1 ) {
456  perror("wge100Discover unable to receive from socket");
457  goto err;
458  }
459 
460  if (packet_len != sizeof(PacketAnnounce))
461  {
462  //if (packet_len != sizeof(PacketAnnounce) - sizeof(aPkt.camera_name) - sizeof(IPAddress))
463  continue; // Not a valid packet
464  /*else // Old announce packet
465  {
466  bzero(aPkt.camera_name, sizeof(aPkt.camera_name));
467  aPkt.camera_ip = fromaddr.sin_addr.s_addr;
468  } */
469  }
470 
471  // Create a new list entry and initialize it
472  IpCamList *tmpListItem;
473  if( (tmpListItem = (IpCamList *)malloc(sizeof(IpCamList))) == NULL ) {
474  perror("Malloc failed");
475  goto err;
476  }
477  wge100CamListInit( tmpListItem );
478 
479  // Initialize the new list item's data fields (byte order corrected)
480  tmpListItem->hw_version = ntohl(aPkt.hw_version);
481  tmpListItem->fw_version = ntohl(aPkt.fw_version);
482  tmpListItem->ip = aPkt.camera_ip;
483  uint8_t *ipbytes = (uint8_t *) &aPkt.camera_ip;
484  snprintf(tmpListItem->ip_str, sizeof(tmpListItem->ip_str), "%i.%i.%i.%i", ipbytes[0], ipbytes[1], ipbytes[2], ipbytes[3]);
485  tmpListItem->serial = ntohl(aPkt.ser_no);
486  memcpy(&tmpListItem->mac, aPkt.mac, sizeof(aPkt.mac));
487  memcpy(tmpListItem->cam_name, aPkt.camera_name, sizeof(aPkt.camera_name));
488  aPkt.camera_name[sizeof(aPkt.camera_name) - 1] = 0;
489  strncpy(tmpListItem->ifName, ifNames[curs], sizeof(tmpListItem->ifName));
490  tmpListItem->ifName[sizeof(tmpListItem->ifName) - 1] = 0;
491  tmpListItem->status = CamStatusDiscovered;
492  char pcb_rev = 0x0A + (0x0000000F & ntohl(aPkt.hw_version));
493  int hdl_rev = 0x00000FFF & (ntohl(aPkt.hw_version)>>4);
494  snprintf(tmpListItem->hwinfo, WGE100_CAMINFO_LEN, "PCB rev %X : HDL rev %3X : FW rev %3X", pcb_rev, hdl_rev, ntohl(aPkt.fw_version));
495 
496  // If this camera is already in the list, we don't want to add another copy
497  if( wge100CamListAdd( ipCamList, tmpListItem ) == CAMLIST_ADD_DUP) {
498  free(tmpListItem);
499  } else {
500  wge100_debug("MAC Address: %02X:%02X:%02X:%02X:%02X:%02X\n", aPkt.mac[0], aPkt.mac[1], aPkt.mac[2], aPkt.mac[3], aPkt.mac[4], aPkt.mac[5]);
501  wge100_debug("Product #%07u : Unit #%04u\n", ntohl(aPkt.product_id), ntohl(aPkt.ser_no));
502  wge100_debug("%s\n", tmpListItem->hwinfo);
503  newCamCount++;
504  }
505  }
506  } while(wait_us > 0);
507  retval = newCamCount;
508 
509 err:
510  if (ifaces)
511  freeifaddrs(ifaces);
512  for (i = 0; i < nums; i++)
513  close(s[i]);
514  free(s);
515  free(ifNames);
516  return retval;
517 }
518 
519 
532 int wge100Configure( IpCamList *camInfo, const char *ipAddress, unsigned wait_us) {
533  // Create and initialize a new Configure packet
534  PacketConfigure cPkt;
535 
536  cPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
537  cPkt.hdr.type = htonl(PKTT_CONFIGURE);
538  cPkt.product_id = htonl(CONFIG_PRODUCT_ID);
539  strncpy(cPkt.hdr.hrt, "CONFIGURE", sizeof(cPkt.hdr.hrt));
540 
541  cPkt.ser_no = htonl(camInfo->serial);
542 
543  // Create and send the Configure broadcast packet. It is sent broadcast
544  // because the camera does not yet have an IP address assigned.
545 
546  /* Create a new socket bound to a local ephemeral port, and get our local connection
547  * info so we can request a reply back to the same socket.
548  */
549  int s = wge100CmdSocketCreate(camInfo->ifName, &cPkt.hdr.reply_to);
550  if(s == -1) {
551  perror("wge100Configure socket creation failed");
552  return -1;
553  }
554 
555  // Figure out the IP to use, and send the packet.
556  if (!ipAddress || !*ipAddress)
557  {
558  wge100_debug("No ipAddress, using %x\n", camInfo->ip);
559  cPkt.ip_addr = camInfo->ip;
560 
561  if(wge100SendUDP(s, &camInfo->ip, &cPkt, sizeof(cPkt)) == -1) {
562  wge100_debug("Unable to send packet\n");
563  close(s);
564  return -1;
565  }
566  }
567  else
568  {
569  struct in_addr newIP;
570  inet_aton(ipAddress, &newIP);
571  cPkt.ip_addr = newIP.s_addr;
572  wge100_debug("Using ipAddress %s -> %x iface %s\n", ipAddress, cPkt.ip_addr, camInfo->ifName);
573 
574  wge100_debug("Sending broadcast discover packet.\n");
575  if(wge100SendUDPBcast(s, camInfo->ifName, &cPkt, sizeof(cPkt)) == -1) {
576  wge100_debug("Unable to send broadcast\n");
577  close(s);
578  return -1;
579  }
580  }
581 
582  // 'Connect' insures we will only receive datagram replies from the camera's new IP
583  IPAddress camIP = cPkt.ip_addr;
584  wge100_debug("Connecting to %x.\n", camIP);
585  if( wge100SocketConnect(s, &camIP) ) {
586  wge100_debug("Unable to connect\n");
587  close(s);
588  return -1;
589  }
590 
591  // Wait up to wait_us for a valid packet to be received on s
592  do {
593  if( wge100WaitForPacket(&s, 1, PKTT_ANNOUNCE, sizeof(PacketAnnounce) - CAMERA_NAME_LEN - sizeof(IPAddress), &wait_us) != -1 && (wait_us != 0) ) {
594  PacketAnnounce aPkt;
595 
596  if( recvfrom( s, &aPkt, sizeof(PacketAnnounce), 0, NULL, NULL ) == -1 ) {
597  perror("wge100Discover unable to receive from socket");
598  close(s);
599  return -1;
600  }
601 
602  // Need to have a valid packet from a camera with the expected serial number
603  if( ntohl(aPkt.ser_no) == camInfo->serial ) {
604  camInfo->status = CamStatusConfigured;
605  memcpy(&camInfo->ip, &cPkt.ip_addr, sizeof(IPAddress));
606  /*// Add the IP/MAC mapping to the system ARP table
607  if( wge100ArpAdd(camInfo) ) {
608  close(s);
609  return ERR_CONFIG_ARPFAIL;
610  } */ // ARP handled by the camera except for obsolete firmware versions.
611  break;
612  }
613  }
614  } while(wait_us > 0);
615  close(s);
616 
617  if(wait_us != 0) {
618  return 0;
619  } else {
620  wge100_debug("Timed out.\n");
621  return ERR_TIMEOUT;
622  }
623 }
624 
638 int wge100StartVid( const IpCamList *camInfo, const uint8_t mac[6], const char *ipAddress, uint16_t port ) {
639  PacketVidStart vPkt;
640 
641  // Initialize the packet
642  vPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
643  vPkt.hdr.type = htonl(PKTT_VIDSTART);
644  strncpy(vPkt.hdr.hrt, "Start Video", sizeof(vPkt.hdr.hrt));
645 
646 
647  // Convert the ipAddress string into a binary value in network byte order
648  inet_aton(ipAddress, (struct in_addr*)&vPkt.receiver.addr);
649 
650  // Convert the receiver port into network byte order
651  vPkt.receiver.port = htons(port);
652 
653  // Copy the MAC address into the vPkt
654  memcpy(&vPkt.receiver.mac, mac, 6);
655 
656  /* Create a new socket bound to a local ephemeral port, and get our local connection
657  * info so we can request a reply back to the same socket.
658  */
659  int s = wge100CmdSocketCreate(camInfo->ifName, &vPkt.hdr.reply_to);
660  if( s == -1 ) {
661  return -1;
662  }
663 
664  if(wge100SendUDP(s, &camInfo->ip, &vPkt, sizeof(vPkt)) == -1) {
665  goto err_out;
666  }
667 
668  // 'Connect' insures we will only receive datagram replies from the camera we've specified
669  if( wge100SocketConnect(s, &camInfo->ip) ) {
670  goto err_out;
671  }
672 
673  // Wait for a status reply
674  uint32_t type, code;
675  if( wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code ) == -1) {
676  goto err_out;
677  }
678 
679  close(s);
680  if(type == PKT_STATUST_OK) {
681  return 0;
682  } else {
683  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
684  return 1;
685  }
686 
687 err_out:
688  close(s);
689  return -1;
690 }
691 
700 int wge100StopVid( const IpCamList *camInfo ) {
701  PacketVidStop vPkt;
702 
703  // Initialize the packet
704  vPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
705  vPkt.hdr.type = htonl(PKTT_VIDSTOP);
706  strncpy(vPkt.hdr.hrt, "Stop Video", sizeof(vPkt.hdr.hrt));
707 
708  /* Create a new socket bound to a local ephemeral port, and get our local connection
709  * info so we can request a reply back to the same socket.
710  */
711  int s = wge100CmdSocketCreate(camInfo->ifName, &vPkt.hdr.reply_to);
712  if( s == -1 ) {
713  return -1;
714  }
715 
716  if( wge100SendUDP(s, &camInfo->ip, &vPkt, sizeof(vPkt)) == -1 ) {
717  goto err_out;
718  }
719 
720  // 'Connect' insures we will only receive datagram replies from the camera we've specified
721  if( wge100SocketConnect(s, &camInfo->ip) == -1) {
722  goto err_out;
723  }
724 
725  uint32_t type, code;
726  if(wge100StatusWait( s, STOP_REPLY_TIMEOUT, &type, &code ) == -1) {
727  goto err_out;
728  }
729 
730  close(s);
731  if(type == PKT_STATUST_OK) {
732  return 0;
733  } else {
734  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
735  return 1;
736  }
737 
738 err_out:
739  close(s);
740  return -1;
741 }
742 
752 
753  // Initialize the packet
754  gPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
755  gPkt.hdr.type = htonl(PKTT_RECONFIG_FPGA);
756  strncpy(gPkt.hdr.hrt, "ReconfigureFPGA", sizeof(gPkt.hdr.hrt));
757 
758  /* Create a new socket bound to a local ephemeral port, and get our local connection
759  * info so we can request a reply back to the same socket.
760  */
761  int s = wge100CmdSocketCreate(camInfo->ifName, &gPkt.hdr.reply_to);
762  if( s == -1 ) {
763  return -1;
764  }
765 
766  if( wge100SendUDP(s, &camInfo->ip, &gPkt, sizeof(gPkt)) == -1 ) {
767  close(s);
768  return -1;
769  }
770 
771  close(s);
772 
773  // Camera is no longer configured after a reset
774  camInfo->status = CamStatusDiscovered;
775 
776  // There is no reply to a reset packet
777 
778  return 0;
779 }
780 
788 int wge100Reset( IpCamList *camInfo ) {
789  PacketReset gPkt;
790 
791  // Initialize the packet
792  gPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
793  gPkt.hdr.type = htonl(PKTT_RESET);
794  strncpy(gPkt.hdr.hrt, "Reset", sizeof(gPkt.hdr.hrt));
795 
796  /* Create a new socket bound to a local ephemeral port, and get our local connection
797  * info so we can request a reply back to the same socket.
798  */
799  int s = wge100CmdSocketCreate(camInfo->ifName, &gPkt.hdr.reply_to);
800  if( s == -1 ) {
801  return -1;
802  }
803 
804  if( wge100SendUDP(s, &camInfo->ip, &gPkt, sizeof(gPkt)) == -1 ) {
805  close(s);
806  return -1;
807  }
808 
809 
810  close(s);
811 
812  // Camera is no longer configured after a reset
813  camInfo->status = CamStatusDiscovered;
814 
815  // There is no reply to a reset packet
816 
817  return 0;
818 }
819 
832 int wge100GetTimer( const IpCamList *camInfo, uint64_t *time_us ) {
833  PacketTimeRequest gPkt;
834 
835  // Initialize the packet
836  gPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
837  gPkt.hdr.type = htonl(PKTT_TIMEREQ);
838  strncpy(gPkt.hdr.hrt, "Time Req", sizeof(gPkt.hdr.hrt));
839 
840  /* Create a new socket bound to a local ephemeral port, and get our local connection
841  * info so we can request a reply back to the same socket.
842  */
843  int s = wge100CmdSocketCreate(camInfo->ifName, &gPkt.hdr.reply_to);
844  if( s == -1 ) {
845  return -1;
846  }
847 
848  if( wge100SendUDP(s, &camInfo->ip, &gPkt, sizeof(gPkt)) == -1 ) {
849  close(s);
850  return -1;
851  }
852 
853  // 'Connect' insures we will only receive datagram replies from the camera we've specified
854  if( wge100SocketConnect(s, &camInfo->ip) ) {
855  close(s);
856  return -1;
857  }
858 
859  uint32_t wait_us = STD_REPLY_TIMEOUT;
860  do {
861  if( wge100WaitForPacket(&s, 1, PKTT_TIMEREPLY, sizeof(PacketTimer), &wait_us) != -1 && (wait_us != 0) ) {
862  PacketTimer tPkt;
863  if( recvfrom( s, &tPkt, sizeof(PacketTimer), 0, NULL, NULL ) == -1 ) {
864  perror("GetTime unable to receive from socket");
865  close(s);
866  return -1;
867  }
868 
869  *time_us = (uint64_t)ntohl(tPkt.ticks_hi) << 32;
870  *time_us += ntohl(tPkt.ticks_lo);
871 
872  // Need to multiply final result by 1E6 to get us from sec
873  // Try to do this to limit loss of precision without overflow
874  // (We will overflow the 64-bit type with this approach
875  // after the camera has been up for about 11 continuous years)
876  //FIXME: Review this algorithm for possible improvements.
877  *time_us *= 1000;
878  *time_us /= (ntohl(tPkt.ticks_per_sec)/1000);
879  //debug("Got time of %llu us since last reset\n", *time_us);
880  close(s);
881  return 0;
882  }
883  } while(wait_us > 0);
884 
885  wge100_debug("Timed out waiting for time value\n");
886  close(s);
887  return 1;
888 }
889 
906 int wge100ReliableFlashRead( const IpCamList *camInfo, uint32_t address, uint8_t *pageDataOut, int *retries ) {
907  int retval = -2;
908 
909  int counter = 10;
910 
911  if (retries == NULL)
912  retries = &counter;
913  for (; *retries > 0; (*retries)--)
914  {
915  retval = wge100FlashRead( camInfo, address, pageDataOut );
916 
917  if (!retval)
918  return 0;
919 
920  wge100_debug("Flash read failed.");
921  }
922 
923  return retval;
924 }
925 
940 int wge100FlashRead( const IpCamList *camInfo, uint32_t address, uint8_t *pageDataOut ) {
941  PacketFlashRequest rPkt;
942 
943  // Initialize the packet
944  rPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
945  rPkt.hdr.type = htonl(PKTT_FLASHREAD);
946  if(address > FLASH_MAX_PAGENO) {
947  return 1;
948  }
949 
950  // The page portion of the address is 12-bits wide, range (bit9..bit21)
951  rPkt.address = htonl(address<<9);
952 
953  strncpy(rPkt.hdr.hrt, "Flash read", sizeof(rPkt.hdr.hrt));
954 
955  /* Create a new socket bound to a local ephemeral port, and get our local connection
956  * info so we can request a reply back to the same socket.
957  */
958  int s = wge100CmdSocketCreate(camInfo->ifName, &rPkt.hdr.reply_to);
959  if( s == -1 ) {
960  return -1;
961  }
962 
963  if( wge100SendUDP(s, &camInfo->ip, &rPkt, sizeof(rPkt)) == -1 ) {
964  close(s);
965  return -1;
966  }
967 
968 
969  // 'Connect' insures we will only receive datagram replies from the camera we've specified
970  if( wge100SocketConnect(s, &camInfo->ip) ) {
971  close(s);
972  return -1;
973  }
974 
975  uint32_t wait_us = STD_REPLY_TIMEOUT;
976  do {
977  if( wge100WaitForPacket(&s, 1, PKTT_FLASHDATA, sizeof(PacketFlashPayload), &wait_us) != -1 && (wait_us != 0) ) {
978  PacketFlashPayload fPkt;
979  if( recvfrom( s, &fPkt, sizeof(PacketFlashPayload), 0, NULL, NULL ) == -1 ) {
980  perror("GetTime unable to receive from socket");
981  close(s);
982  return -1;
983  }
984 
985  // Copy the received data into the space pointed to by pageDataOut
986  memcpy(pageDataOut, fPkt.data, FLASH_PAGE_SIZE);
987  close(s);
988  return 0;
989  }
990  } while(wait_us > 0);
991 
992  wge100_debug("Timed out waiting for flash value\n");
993  close(s);
994  return 1;
995 }
996 
1014 int wge100ReliableFlashWrite( const IpCamList *camInfo, uint32_t address, const uint8_t *pageDataIn, int *retries ) {
1015  uint8_t buffer[FLASH_PAGE_SIZE];
1016  int retval = -2;
1017  int counter = 10;
1018  int first_read = 1;
1019 
1020  if (retries == NULL)
1021  retries = &counter;
1022 
1023  (*retries)++; // Don't count the first read as a retry.
1024  goto read_first; // Don't bother writing if nothing has changed.
1025 
1026  for (; *retries > 0; (*retries)--)
1027  {
1028  //printf("Trying write.\n");
1029  retval = wge100FlashWrite( camInfo, address, pageDataIn );
1030  if (retval)
1031  {
1032  wge100_debug("Failed write, retries left: %i.", *retries);
1033  //printf("Failed compare write.\n");
1034  continue;
1035  }
1036 
1037  first_read = 0;
1038 read_first:
1039  retval = wge100ReliableFlashRead( camInfo, address, buffer, retries );
1040  if (retval)
1041  {
1042  //if (!first_read)
1043  // wge100_debug("Failed compare read.");
1044  //else
1045  //printf("First read failed.\n");
1046  //printf("Failed compare read.\n");
1047  continue;
1048  }
1049 
1050  if (!memcmp(buffer, pageDataIn, FLASH_PAGE_SIZE))
1051  return 0;
1052  //if (!first_read)
1053  // wge100_debug("Failed compare.");
1054  //else
1055  //printf("First read mismatch.\n");
1056  //printf("Failed compare.\n");
1057 
1058  if (*retries == 0) // In case retries ran out during the read.
1059  break;
1060  }
1061 
1062  return retval;
1063 }
1064 
1077 int wge100FlashWrite( const IpCamList *camInfo, uint32_t address, const uint8_t *pageDataIn ) {
1078  PacketFlashPayload rPkt;
1079 
1080  // Initialize the packet
1081  rPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1082  rPkt.hdr.type = htonl(PKTT_FLASHWRITE);
1083  if(address > FLASH_MAX_PAGENO) {
1084  return 1;
1085  }
1086 
1087  // The page portion of the address is 12-bits wide, range (bit9..bit21)
1088  rPkt.address = htonl(address<<9);
1089  strncpy(rPkt.hdr.hrt, "Flash write", sizeof(rPkt.hdr.hrt));
1090 
1091  memcpy(rPkt.data, pageDataIn, FLASH_PAGE_SIZE);
1092 
1093  /* Create a new socket bound to a local ephemeral port, and get our local connection
1094  * info so we can request a reply back to the same socket.
1095  */
1096  int s = wge100CmdSocketCreate(camInfo->ifName, &rPkt.hdr.reply_to);
1097  if( s == -1 ) {
1098  return -1;
1099  }
1100 
1101  if( wge100SendUDP(s, &camInfo->ip, &rPkt, sizeof(rPkt)) == -1 ) {
1102  close(s);
1103  return -1;
1104  }
1105 
1106  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1107  if( wge100SocketConnect(s, &camInfo->ip) ) {
1108  close(s);
1109  return -1;
1110  }
1111 
1112  // Wait for response - once we get an OK, we're clear to send the next page.
1113  uint32_t type, code;
1114  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1115 
1116  close(s);
1117  if(type == PKT_STATUST_OK) {
1118  return 0;
1119  } else {
1120  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1121  return 1;
1122  }
1123 }
1124 
1135 int wge100TriggerControl( const IpCamList *camInfo, uint32_t triggerType ) {
1136  PacketTrigControl tPkt;
1137 
1138  // Initialize the packet
1139  tPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1140  tPkt.hdr.type = htonl(PKTT_TRIGCTRL);
1141  tPkt.trig_state = htonl(triggerType);
1142 
1143  if(triggerType == TRIG_STATE_INTERNAL ) {
1144  strncpy(tPkt.hdr.hrt, "Int. Trigger", sizeof(tPkt.hdr.hrt));
1145  } else {
1146  strncpy(tPkt.hdr.hrt, "Ext. Trigger", sizeof(tPkt.hdr.hrt));
1147  }
1148 
1149  /* Create a new socket bound to a local ephemeral port, and get our local connection
1150  * info so we can request a reply back to the same socket.
1151  */
1152  int s = wge100CmdSocketCreate(camInfo->ifName, &tPkt.hdr.reply_to);
1153  if( s == -1 ) {
1154  return -1;
1155  }
1156 
1157  if( wge100SendUDP(s, &camInfo->ip, &tPkt, sizeof(tPkt)) == -1 ) {
1158  close(s);
1159  return -1;
1160  }
1161 
1162  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1163  if( wge100SocketConnect(s, &camInfo->ip) ) {
1164  close(s);
1165  return -1;
1166  }
1167 
1168  // Wait for response
1169  uint32_t type, code;
1170  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1171 
1172  close(s);
1173  if(type == PKT_STATUST_OK) {
1174  return 0;
1175  } else {
1176  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1177  return 1;
1178  }
1179 }
1180 
1194 int wge100ConfigureBoard( const IpCamList *camInfo, uint32_t serial, MACAddress *mac ) {
1195  PacketSysConfig sPkt;
1196 
1197  // Initialize the packet
1198  sPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1199  sPkt.hdr.type = htonl(PKTT_SYSCONFIG);
1200 
1201  strncpy(sPkt.hdr.hrt, "System Config", sizeof(sPkt.hdr.hrt));
1202  memcpy(&sPkt.mac, mac, 6);
1203  sPkt.serial = htonl(serial);
1204 
1205 
1206  /* Create a new socket bound to a local ephemeral port, and get our local connection
1207  * info so we can request a reply back to the same socket.
1208  */
1209  int s = wge100CmdSocketCreate(camInfo->ifName, &sPkt.hdr.reply_to);
1210  if( s == -1 ) {
1211  return -1;
1212  }
1213 
1214  if( wge100SendUDP(s, &camInfo->ip, &sPkt, sizeof(sPkt)) == -1 ) {
1215  close(s);
1216  return -1;
1217  }
1218 
1219  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1220  if( wge100SocketConnect(s, &camInfo->ip) ) {
1221  close(s);
1222  return -1;
1223  }
1224  // Wait for response
1225  uint32_t type, code;
1226  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1227 
1228  close(s);
1229  if(type == PKT_STATUST_OK) {
1230  return 0;
1231  } else {
1232  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1233  return 1;
1234  }
1235 }
1236 
1252 int wge100ReliableSensorWrite( const IpCamList *camInfo, uint8_t reg, uint16_t data, int *retries ) {
1253  uint16_t readbackdata;
1254  int retval = -2;
1255  int counter = 10;
1256 
1257  if (retries == NULL)
1258  retries = &counter;
1259 
1260  for (; *retries > 0; (*retries)--)
1261  {
1262  retval = wge100SensorWrite( camInfo, reg, data );
1263  if (retval)
1264  continue;
1265 
1266  retval = wge100ReliableSensorRead( camInfo, reg, &readbackdata, retries );
1267  if (retval)
1268  continue;
1269 
1270  if (readbackdata == data)
1271  return 0;
1272 
1273  if (*retries == 0) // In case retries ran out during the read.
1274  retval = -2;
1275  }
1276 
1277  return retval;
1278 }
1279 
1291 int wge100SensorWrite( const IpCamList *camInfo, uint8_t reg, uint16_t data ) {
1292  PacketSensorData sPkt;
1293 
1294  // Initialize the packet
1295  sPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1296  sPkt.hdr.type = htonl(PKTT_SENSORWR);
1297 
1298  strncpy(sPkt.hdr.hrt, "Write I2C", sizeof(sPkt.hdr.hrt));
1299  sPkt.address = reg;
1300  sPkt.data = htons(data);
1301 
1302  /* Create a new socket bound to a local ephemeral port, and get our local connection
1303  * info so we can request a reply back to the same socket.
1304  */
1305  int s = wge100CmdSocketCreate(camInfo->ifName, &sPkt.hdr.reply_to);
1306  if( s == -1 ) {
1307  return -1;
1308  }
1309 
1310  if( wge100SendUDP(s, &camInfo->ip, &sPkt, sizeof(sPkt)) == -1 ) {
1311  close(s);
1312  return -1;
1313  }
1314 
1315  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1316  if( wge100SocketConnect(s, &camInfo->ip) ) {
1317  close(s);
1318  return -1;
1319  }
1320 
1321  // Wait for response
1322  uint32_t type, code;
1323  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1324 
1325  close(s);
1326  if(type == PKT_STATUST_OK) {
1327  return 0;
1328  } else {
1329  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1330  return 1;
1331  }
1332 }
1333 
1349 int wge100ReliableSensorRead( const IpCamList *camInfo, uint8_t reg, uint16_t *data, int *retries ) {
1350  int retval = -2;
1351 
1352  int counter = 10;
1353 
1354  if (retries == NULL)
1355  retries = &counter;
1356  for (; *retries > 0; (*retries)--)
1357  {
1358  retval = wge100SensorRead( camInfo, reg, data );
1359 
1360  if (!retval)
1361  return 0;
1362  }
1363 
1364  return retval;
1365 }
1366 
1378 int wge100SensorRead( const IpCamList *camInfo, uint8_t reg, uint16_t *data ) {
1379  PacketSensorRequest rPkt;
1380 
1381  // Initialize the packet
1382  rPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1383  rPkt.hdr.type = htonl(PKTT_SENSORRD);
1384  rPkt.address = reg;
1385  strncpy(rPkt.hdr.hrt, "Read I2C", sizeof(rPkt.hdr.hrt));
1386 
1387  /* Create a new socket bound to a local ephemeral port, and get our local connection
1388  * info so we can request a reply back to the same socket.
1389  */
1390  int s = wge100CmdSocketCreate(camInfo->ifName, &rPkt.hdr.reply_to);
1391  if( s == -1 ) {
1392  return -1;
1393  }
1394 
1395  if( wge100SendUDP(s, &camInfo->ip, &rPkt, sizeof(rPkt)) == -1 ) {
1396  close(s);
1397  return -1;
1398  }
1399 
1400  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1401  if( wge100SocketConnect(s, &camInfo->ip) ) {
1402  close(s);
1403  return -1;
1404  }
1405 
1406  uint32_t wait_us = STD_REPLY_TIMEOUT;
1407  do {
1408  if( wge100WaitForPacket(&s, 1, PKTT_SENSORDATA, sizeof(PacketSensorData), &wait_us) != -1 && (wait_us != 0) ) {
1409  PacketSensorData sPkt;
1410  if( recvfrom( s, &sPkt, sizeof(PacketSensorData), 0, NULL, NULL ) == -1 ) {
1411  perror("SensorRead unable to receive from socket");
1412  close(s);
1413  return -1;
1414  }
1415 
1416  *data = ntohs(sPkt.data);
1417  close(s);
1418  return 0;
1419  }
1420  } while(wait_us > 0);
1421 
1422  wge100_debug("Timed out waiting for sensor value\n");
1423  close(s);
1424  return 1;
1425 }
1426 
1438 int wge100SensorSelect( const IpCamList *camInfo, uint8_t index, uint32_t reg ) {
1439  PacketSensorSelect sPkt;
1440 
1441  // Initialize the packet
1442  sPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1443  sPkt.hdr.type = htonl(PKTT_SENSORSEL);
1444 
1445  strncpy(sPkt.hdr.hrt, "Select I2C", sizeof(sPkt.hdr.hrt));
1446  sPkt.index = index;
1447  sPkt.address = htonl(reg);
1448 
1449  /* Create a new socket bound to a local ephemeral port, and get our local connection
1450  * info so we can request a reply back to the same socket.
1451  */
1452  int s = wge100CmdSocketCreate(camInfo->ifName, &sPkt.hdr.reply_to);
1453  if( s == -1 ) {
1454  return -1;
1455  }
1456 
1457  if( wge100SendUDP(s, &camInfo->ip, &sPkt, sizeof(sPkt)) == -1 ) {
1458  close(s);
1459  return -1;
1460  }
1461 
1462  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1463  if( wge100SocketConnect(s, &camInfo->ip) ) {
1464  close(s);
1465  return -1;
1466  }
1467 
1468  // Wait for response
1469  uint32_t type, code;
1470  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1471 
1472  close(s);
1473  if(type == PKT_STATUST_OK) {
1474  return 0;
1475  } else {
1476  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1477  return 1;
1478  }
1479 }
1480 
1491 int wge100ImagerModeSelect( const IpCamList *camInfo, uint32_t mode ) {
1492  PacketImagerMode mPkt;
1493 
1494  // Initialize the packet
1495  mPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1496  mPkt.hdr.type = htonl(PKTT_IMGRMODE);
1497 
1498  mPkt.mode = htonl(mode);
1499 
1500  strncpy(mPkt.hdr.hrt, "Set Mode", sizeof(mPkt.hdr.hrt));
1501 
1502  /* Create a new socket bound to a local ephemeral port, and get our local connection
1503  * info so we can request a reply back to the same socket.
1504  */
1505  int s = wge100CmdSocketCreate(camInfo->ifName, &mPkt.hdr.reply_to);
1506  if( s == -1 ) {
1507  return -1;
1508  }
1509 
1510  if( wge100SendUDP(s, &camInfo->ip, &mPkt, sizeof(mPkt)) == -1 ) {
1511  close(s);
1512  return -1;
1513  }
1514 
1515  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1516  if( wge100SocketConnect(s, &camInfo->ip) ) {
1517  close(s);
1518  return -1;
1519  }
1520 
1521  // Wait for response
1522  uint32_t type, code;
1523  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1524 
1525  close(s);
1526  if(type == PKT_STATUST_OK) {
1527  return 0;
1528  } else {
1529  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1530  return 1;
1531  }
1532 }
1533 
1548 int wge100ImagerSetRes( const IpCamList *camInfo, uint16_t horizontal, uint16_t vertical ) {
1549  PacketImagerSetRes rPkt;
1550 
1551  // Initialize the packet
1552  rPkt.hdr.magic_no = htonl(WG_MAGIC_NO);
1553  rPkt.hdr.type = htonl(PKTT_IMGRSETRES);
1554 
1555  rPkt.horizontal = htons(horizontal);
1556  rPkt.vertical = htons(vertical);
1557 
1558  strncpy(rPkt.hdr.hrt, "Set Res", sizeof(rPkt.hdr.hrt));
1559 
1560  /* Create a new socket bound to a local ephemeral port, and get our local connection
1561  * info so we can request a reply back to the same socket.
1562  */
1563  int s = wge100CmdSocketCreate(camInfo->ifName, &rPkt.hdr.reply_to);
1564  if( s == -1 ) {
1565  return -1;
1566  }
1567 
1568  if( wge100SendUDP(s, &camInfo->ip, &rPkt, sizeof(rPkt)) == -1 ) {
1569  close(s);
1570  return -1;
1571  }
1572 
1573  // 'Connect' insures we will only receive datagram replies from the camera we've specified
1574  if( wge100SocketConnect(s, &camInfo->ip) ) {
1575  close(s);
1576  return -1;
1577  }
1578 
1579  // Wait for response
1580  uint32_t type, code;
1581  wge100StatusWait( s, STD_REPLY_TIMEOUT, &type, &code );
1582 
1583  close(s);
1584  if(type == PKT_STATUST_OK) {
1585  return 0;
1586  } else {
1587  wge100_debug("Error: wge100StatusWait returned status %d, code %d\n", type, code);
1588  return 1;
1589  }
1590 }
1591 
1592 #define MAX_HORIZ_RESOLUTION 752
1593 #define LINE_NUMBER_MASK 0x3FF
1594 
1595 int wge100VidReceiveSocket( int s, size_t height, size_t width, FrameHandler frameHandler, void *userData ) {
1596  /*
1597  * The default receive buffer size on a 32-bit Linux machine is only 128kB.
1598  * At a burst data rate of ~ 82.6Mbit/s in the 640x480 @30fps, this buffer will fill in ~12.6ms.
1599  * With the default Linux scheduler settings, this leaves virtually no time for any other processes
1600  * to execute before the buffer overflows. Increasing the buffer reduces the chance of lost
1601  * packets.
1602  *
1603  * The 8MB buffer here is far larger than necessary for most applications and may be reduced with
1604  * some experimentation.
1605  *
1606  * Note that the Linux system command 'sysctl -w net.core.rmem_max=8388608' must be used to enable
1607  * receive buffers larger than the kernel default.
1608  */
1609  size_t bufsize = 16*1024*1024; // 8MB receive buffer.
1610 
1611  int i;
1612 
1613  int return_value = 0;
1614 
1615  if( setsockopt(s, SOL_SOCKET,SO_RCVBUF, &bufsize, sizeof(bufsize)) == -1) {
1616  perror("Can't set rcvbuf option");
1617  close(s);
1618  return -1;
1619  }
1620 
1621  socklen_t bufsizesize = sizeof(bufsize);
1622  if( getsockopt(s, SOL_SOCKET,SO_RCVBUF, &bufsize, &bufsizesize) == 0) {
1623  wge100_debug("Receive buffer size is: %i (%i)\n", bufsize, bufsizesize);
1624  }
1625  else
1626  {
1627  perror("Can't read receive buffer size");
1628  }
1629 
1630  // We receive data one line at a time; lines will be reassembled into this buffer as they arrive
1631  uint8_t *frame_buf;
1632  frame_buf = malloc(sizeof(uint8_t)*width*height);
1633  if(frame_buf == NULL) {
1634  perror("Can't malloc frame buffer");
1635  close(s);
1636  return -1;
1637  }
1638 
1639  // Allocate enough storage for the header as well as 'width' bytes of video data
1640  PacketVideoLine *vPkt=malloc(sizeof(PacketVideoLine));
1641  if(vPkt == NULL) {
1642  perror("Can't malloc line packet buffer");
1643  close(s);
1644  return -1;
1645  }
1646 
1647  // Flag to indicate that 'frameInfo.frame_number' has not yet been set
1648  bool firstPacket = true;
1649 
1650  // Flag to indicate the current frame is complete (either EOF received or first line of next frame received)
1651  bool frameComplete;
1652 
1653  // Flag to indicate that we have set the 'frameInfo.startTime' timeval for this frame.
1654  bool frameStartTimeSet;
1655 
1656  // Holds return code from frameHandler
1657  int handlerReturn;
1658 
1659  // Counts number of lines received in current frame
1660  uint32_t lineCount;
1661 
1662  // Points to an EOF structure for passing to frameHandler;
1663  PacketEOF *eof = NULL;
1664 
1665  // Information structure to pass to the frame handler.
1666  wge100FrameInfo frameInfo;
1667 
1668  // Keep track of where the last packet came from (to send out pings).
1669  struct sockaddr_in fromaddr;
1670 
1671  // Has the current frame had an XOR line
1672  bool has_xor;
1673 
1674  frameInfo.width = width;
1675  frameInfo.height = height;
1676 
1677  uint8_t xorline[width];
1678 
1679  do {
1680  lineCount = 0;
1681  frameComplete = false;
1682  frameStartTimeSet = false;
1683  frameInfo.lastMissingLine = -1;
1684  frameInfo.missingLines = 0;
1685  frameInfo.shortFrame = false;
1686  frameInfo.frame_number = vPkt->header.frame_number+1;
1687  // Ensure the buffer is cleared out. Makes viewing short packets less confusing; missing lines will be black.
1688  memset(frame_buf, 0, width*height);
1689  has_xor = false;
1690 
1691  // We detect a dropped EOF by unexpectedly receiving a line from the next frame before getting the EOF from this frame.
1692  // After the last frame has been processed, start a fresh frame with the expected line.
1693  if( (eof==NULL) && (firstPacket==false) ) {
1694  if(vPkt->header.line_number < height ) {
1695  memcpy(&(frame_buf[vPkt->header.line_number*width]), vPkt->data, width);
1696  lineCount++;
1697  }
1698  frameInfo.frame_number &= ~0xFFFF;
1699  frameInfo.frame_number |= vPkt->header.frame_number;
1700  }
1701 
1702  do {
1703  // Wait forever for video packets to arrive; could use select() with a timeout here if a timeout is needed
1704  struct timeval readtimeout;
1705  fd_set set;
1706  socklen_t fromaddrlen = sizeof(struct sockaddr_in);
1707  fromaddr.sin_family = AF_INET;
1708 
1709  // Wait for either a packet to be received or for timeout
1710  handlerReturn = 0;
1711  do {
1712  readtimeout.tv_sec = 1;
1713  readtimeout.tv_usec = 0;
1714 
1715  FD_ZERO(&set);
1716  FD_SET(s, &set);
1717 
1718  if( select(s+1, &set, NULL, NULL, &readtimeout) == -1 ) {
1719  perror("wge100VidReceive select failed");
1720  close(s);
1721  return -1;
1722  }
1723 
1724  // Call the frame handler with NULL to see if we should bail out.
1725  if(! FD_ISSET(s, &set) && errno != EINTR) {
1726  wge100_debug("Select timed out. Calling handler.");
1727  handlerReturn = frameHandler(NULL, userData);
1728  if (handlerReturn)
1729  break;
1730  }
1731  } while (! FD_ISSET(s, &set));
1732 
1733  // We timed out, and the handler returned nonzero.
1734  if (handlerReturn)
1735  break;
1736 
1737  if( recvfrom( s, vPkt, sizeof(HeaderVideoLine)+width, 0, (struct sockaddr *) &fromaddr, &fromaddrlen ) == -1 ) {
1738  perror("wge100VidReceive unable to receive from socket");
1739  break;
1740  }
1741 
1742  // Convert fields to host byte order for easier processing
1743  vPkt->header.frame_number = ntohl(vPkt->header.frame_number);
1744  vPkt->header.line_number = ntohs(vPkt->header.line_number);
1745  vPkt->header.horiz_resolution = ntohs(vPkt->header.horiz_resolution);
1746  vPkt->header.vert_resolution = ntohs(vPkt->header.vert_resolution);
1747 
1748  //debug("frame: #%i line: %i\n", vPkt->header.frame_number, 0x3FF & vPkt->header.line_number);
1749 
1750  // Check to make sure the frame number information is consistent within the packet
1751  uint16_t temp = (vPkt->header.line_number>>10) & 0x003F;
1752  if (((vPkt->header.line_number & IMAGER_MAGICLINE_MASK) == 0) && (temp != (vPkt->header.frame_number & 0x003F))) {
1753  wge100_debug("Mismatched line/frame numbers: %02X / %02X\n", temp, (vPkt->header.frame_number & 0x003F));
1754  }
1755 
1756  // Validate that the frame is the size we expected
1757  if( (vPkt->header.horiz_resolution != width) || (vPkt->header.vert_resolution != height) ) {
1758  wge100_debug("Invalid frame size received: %u x %u, expected %u x %u\n", vPkt->header.horiz_resolution, vPkt->header.vert_resolution, width, height);
1759  close(s);
1760  return 1;
1761  }
1762 
1763  // First time through we need to initialize the number of the first frame we received
1764  if(firstPacket == true) {
1765  firstPacket = false;
1766  frameInfo.frame_number = vPkt->header.frame_number;
1767  }
1768 
1769  // Store the start time for the frame.
1770  if (!frameStartTimeSet)
1771  {
1772  gettimeofday(&frameInfo.startTime, NULL);
1773  frameStartTimeSet = true;
1774  }
1775 
1776  // Check for frames that ended with an error
1777  if( (vPkt->header.line_number == IMAGER_LINENO_ERR) ||
1778  (vPkt->header.line_number == IMAGER_LINENO_OVF) ) {
1779  wge100_debug("Video error: %04X\n", vPkt->header.line_number);
1780 
1781  // In the case of these special 'error' EOF packets, there has been a serious internal camera failure
1782  // so we will abort rather than try to process the last frame.
1783  return_value = vPkt->header.line_number;
1784  break;
1785  } else if (vPkt->header.line_number == IMAGER_LINENO_ABORT) {
1786  wge100_debug("Video aborted\n");
1787  break; //don't process last frame
1788  } else if((vPkt->header.frame_number - frameInfo.frame_number) & 0xFFFF) { // The camera only sends 16 bits of frame number
1789  // If we have received a line from the next frame, we must have missed the EOF somehow
1790  wge100_debug("Frame #%u missing EOF, got %i lines\n", frameInfo.frame_number, lineCount);
1791  frameComplete = true;
1792  // EOF was missing
1793  eof = NULL;
1794  } else if( vPkt->header.line_number == IMAGER_LINENO_XOR ) {
1795  memcpy(xorline, vPkt->data, width);
1796  has_xor = true;
1797  } else if( vPkt->header.line_number == IMAGER_LINENO_EOF ) {
1798  // This is a 'normal' (non-error) end of frame packet (line number 0x3FF)
1799  frameComplete = true;
1800 
1801  // Handle EOF data fields
1802  eof = (PacketEOF *)vPkt;
1803 
1804  // Correct to network byte order for frameHandler
1805  eof->ticks_hi = ntohl(eof->ticks_hi);
1806  eof->ticks_lo = ntohl(eof->ticks_lo);
1807  eof->ticks_per_sec = ntohl(eof->ticks_per_sec);
1808 
1809  // Correct to network byte order for frameHandler
1810  eof->i2c_valid = ntohl(eof->i2c_valid);
1811  for(i=0; i<I2C_REGS_PER_FRAME; i++) {
1812  eof->i2c[i] = ntohs(eof->i2c[i]);
1813  }
1814 
1815  if(lineCount != height) {
1816  if ((1 == (height - lineCount)) && has_xor) {
1817  wge100_debug("Restoring line %i\n", frameInfo.lastMissingLine);
1818 
1819  // reconstruct the missing line by XORing the frame's XOR line
1820  // with every *other* line in the frame.
1821  uint8_t *repair = &frame_buf[frameInfo.lastMissingLine * width];
1822  memcpy(repair, xorline, width);
1823  unsigned int y;
1824  for (y = 0; y < height; y++) {
1825  if (y != frameInfo.lastMissingLine) {
1826  xormem(repair, &frame_buf[y * width], width);
1827  }
1828  }
1829  } else {
1830  // Flag packet as being short for the frameHandler
1832  frameInfo.shortFrame = true;
1833  frameInfo.missingLines = height - lineCount;
1834  }
1835  }
1836  // Move to the next frame
1837 
1838  } else {
1839  // Remove extraneous frame information from the line number field
1841 
1842  if(lineCount > height)
1843  {
1844  wge100_debug("Too many lines received for frame!\n")
1845  break;
1846  }
1847 
1848  if( vPkt->header.line_number >= vPkt->header.vert_resolution ) {
1849  wge100_debug("Invalid line number received: %u (max %u)\n", vPkt->header.line_number, vPkt->header.vert_resolution);
1850  break;
1851  }
1852  if (lineCount + frameInfo.missingLines < vPkt->header.line_number)
1853  {
1854  int missedLines = vPkt->header.line_number - lineCount - frameInfo.missingLines;
1855  frameInfo.lastMissingLine = vPkt->header.line_number - 1;
1856  wge100_debug("Frame #%i missed %i line(s) starting at %i src port %i\n", vPkt->header.frame_number,
1857  missedLines, lineCount + frameInfo.missingLines, ntohs(fromaddr.sin_port));
1858  frameInfo.missingLines += missedLines;
1859  }
1860  memcpy(&(frame_buf[vPkt->header.line_number*width]), vPkt->data, width);
1861  lineCount++;
1862  }
1863  } while(frameComplete == false);
1864 
1865  if( frameComplete == true ) {
1866  frameInfo.frameData = frame_buf;
1867  frameInfo.eofInfo = eof;
1868  frameInfo.frame_number = frameInfo.frame_number;
1869  handlerReturn = frameHandler(&frameInfo, userData);
1870 
1871  // Send a packet to the camera (this ensures that the switches along
1872  // the way won't time out). We could get away with doing this a lot
1873  // less often, but it is a relatively small cost.
1874  uint8_t dummy = 0xff;
1875  if( sendto( s, &dummy, sizeof(dummy), 0, (struct sockaddr *) &fromaddr, sizeof(fromaddr) ) == -1 ) {
1876  handlerReturn = -1; // Should not happen, bail out...
1877  }
1878  } else {
1879  // We wind up here if a serious error has resulted in us 'break'ing out of the loop.
1880  // We won't call frameHandler, we'll just exit directly.
1881  handlerReturn = -1;
1882  }
1883  } while( handlerReturn == 0 );
1884 
1885  close(s);
1886  return return_value;
1887 }
1888 
1889 int wge100VidReceive( const char *ifName, uint16_t port, size_t height, size_t width, FrameHandler frameHandler, void *userData ) {
1890  struct in_addr host_addr;
1891  wge100IpGetLocalAddr( ifName, &host_addr );
1892 
1893  if( frameHandler == NULL ) {
1894  wge100_debug("Invalid frame handler, aborting.\n");
1895  return 1;
1896  }
1897 
1898  wge100_debug("wge100VidReceive ready to receive on %s (%s:%u)\n", ifName, inet_ntoa(host_addr), port);
1899 
1900  int s = wge100SocketCreate( &host_addr, port );
1901  if( s == -1 ) {
1902  return -1;
1903  }
1904 
1905  return wge100VidReceiveSocket( s, height, width, frameHandler, userData);
1906 }
1907 
1908 int wge100VidReceiveAuto( IpCamList *camera, size_t height, size_t width, FrameHandler frameHandler, void *userData ) {
1909  struct sockaddr localMac;
1910  struct in_addr localIp;
1911  struct sockaddr localPort;
1912  socklen_t localPortLen;
1913  int s;
1914  int retval;
1915  int port;
1916 
1917  if ( wge100IpGetLocalAddr(camera->ifName, &localIp) != 0) {
1918  fprintf(stderr, "Unable to get local IP address for interface %s", camera->ifName);
1919  return -1;
1920  }
1921 
1922  if ( wge100EthGetLocalMac(camera->ifName, &localMac) != 0 ) {
1923  fprintf(stderr, "Unable to get local MAC address for interface %s", camera->ifName);
1924  return -1;
1925  }
1926 
1927  if( frameHandler == NULL ) {
1928  wge100_debug("Invalid frame handler, aborting.\n");
1929  return 1;
1930  }
1931 
1932  s = wge100SocketCreate( &localIp, 0 );
1933  if( s == -1 ) {
1934  return -1;
1935  }
1936 
1937  localPortLen = sizeof(localPort);
1938  if (getsockname(s, &localPort, &localPortLen) == -1)
1939  {
1940  fprintf(stderr, "Unable to get local port for socket.");
1941  close(s);
1942  return -1;
1943  }
1944 
1945  port = ntohs(((struct sockaddr_in *)&localPort)->sin_port);
1946 // fprintf(stderr, "Streaming to port %i.\n", port);
1947 
1948  wge100_debug("wge100VidReceiveAuto ready to receive on %s (%s:%u)\n", camera->ifName, inet_ntoa(localIp), port);
1949 
1950  if ( wge100StartVid( camera, (uint8_t *)&(localMac.sa_data[0]), inet_ntoa(localIp), port) != 0 )
1951  {
1952  wge100_debug("Could not start camera streaming.");
1953  close (s);
1954  return -1;
1955  }
1956 
1957  retval = wge100VidReceiveSocket( s, height, width, frameHandler, userData);
1958 
1959  close(s);
1960  wge100StopVid(camera);
1961  return retval;
1962 }
1963 
#define PKTT_SENSORDATA
Definition: ipcam_packet.h:131
#define FLASH_PAGE_SIZE
Definition: ipcam_packet.h:60
int wge100IpGetLocalAddr(const char *ifName, struct in_addr *addr)
Definition: host_netutil.c:231
MACAddress mac
Definition: ipcam_packet.h:79
int wge100CamListAdd(IpCamList *ipCamList, IpCamList *newItem)
Definition: list.c:65
int wge100SocketCreate(const struct in_addr *addr, uint16_t port)
Definition: host_netutil.c:306
#define PKTT_TRIGCTRL
Definition: ipcam_packet.h:117
struct list_head list
Definition: list.h:300
int wge100VidReceiveSocket(int s, size_t height, size_t width, FrameHandler frameHandler, void *userData)
Definition: wge100lib.c:1595
int wge100WaitForPacket(int *s, int nums, uint32_t type, size_t pktLen, uint32_t *wait_us)
Definition: host_netutil.c:493
char hwinfo[WGE100_CAMINFO_LEN]
Definition: list.h:302
uint32_t type
The packet type (see list of packet types, above)
Definition: ipcam_packet.h:156
#define PKTT_SENSORWR
Definition: ipcam_packet.h:119
#define STOP_REPLY_TIMEOUT
Definition: wge100lib.c:51
int wge100SendUDP(int s, const IPAddress *ip, const void *data, size_t dataSize)
Definition: host_netutil.c:435
int wge100StatusWait(int s, uint32_t wait_us, uint32_t *type, uint32_t *code)
Definition: wge100lib.c:287
int wge100ConfigureBoard(const IpCamList *camInfo, uint32_t serial, MACAddress *mac)
Definition: wge100lib.c:1194
int wge100libVersion()
Definition: wge100lib.c:59
IpCamStatus status
Definition: list.h:298
uint32_t hw_version
Definition: ipcam_packet.h:640
int wge100Reset(IpCamList *camInfo)
Definition: wge100lib.c:788
#define PKTT_FLASHREAD
Definition: ipcam_packet.h:115
#define PKTT_RESET
Definition: ipcam_packet.h:113
#define PKT_ERROR_SYSERR
An internal system error occurred.
Definition: ipcam_packet.h:578
#define PKTT_VIDSTOP
Definition: ipcam_packet.h:112
int wge100Configure(IpCamList *camInfo, const char *ipAddress, unsigned wait_us)
Definition: wge100lib.c:532
XmlRpcServer s
HeaderVideoLine header
Standard video line header.
Definition: ipcam_packet.h:697
size_t lastMissingLine
Definition: wge100lib.h:73
uint8_t index
The index of the register in the EOF packet (range 0..3)
Definition: ipcam_packet.h:474
uint8_t data[FLASH_PAGE_SIZE]
32-bit address as specified in the PacketFlashPayload definition
Definition: ipcam_packet.h:376
#define TRIG_STATE_INTERNAL
Definition: wge100lib.h:58
uint32_t frame_number
Definition: wge100lib.h:71
uint8_t MACAddress[6]
Definition: ipcam_packet.h:75
#define PKTT_SENSORSEL
Definition: ipcam_packet.h:120
size_t height
Definition: wge100lib.h:69
static void xormem(uint8_t *dst, uint8_t *src, size_t w)
Definition: wge100lib.c:308
IPAddress ip
Definition: list.h:295
uint16_t line_number
Frame/line number as reported by Imager peripheral.
Definition: ipcam_packet.h:682
int wge100ImagerSetRes(const IpCamList *camInfo, uint16_t horizontal, uint16_t vertical)
Definition: wge100lib.c:1548
#define PKTT_SYSCONFIG
Definition: ipcam_packet.h:123
int wge100Discover(const char *ifName, IpCamList *ipCamList, const char *ipAddress, unsigned wait_us)
Definition: wge100lib.c:372
IPAddress camera_ip
The default power-up IP address for the camera.
Definition: ipcam_packet.h:632
#define IMAGER_LINENO_SHORT
Flags a frame as Short (used only by the library)
Definition: ipcam_packet.h:671
NetHost reply_to
All packet replies should be directed to this host.
Definition: ipcam_packet.h:158
uint32_t status_code
Response code (Error type, etc)
Definition: ipcam_packet.h:592
#define CAMLIST_ADD_DUP
Definition: list.h:316
PacketEOF * eofInfo
Definition: wge100lib.h:78
int wge100CmdSocketCreate(const char *ifName, NetHost *localHost)
Definition: host_netutil.c:387
char hrt[16]
A human-readable text field describing the packet contents.
Definition: ipcam_packet.h:157
IPAddress ip_addr
IP Address device should use when responding.
Definition: ipcam_packet.h:205
#define PKT_ERROR_TIMEOUT
No valid response was received during the allotted interval.
Definition: ipcam_packet.h:577
#define PKTT_TIMEREPLY
Definition: ipcam_packet.h:128
int wge100IpGetLocalNetmask(const char *ifName, struct in_addr *bcast)
Definition: host_netutil.c:269
#define WGE100LIB_VERSION
Definition: wge100lib.h:51
#define IMAGER_MAGICLINE_MASK
Line numbers that match this mask are reserved to indicate special packet types.
Definition: ipcam_packet.h:656
uint32_t IPAddress
Definition: ipcam_packet.h:74
#define PKTT_STATUS
Definition: ipcam_packet.h:129
int wge100VidReceiveAuto(IpCamList *camera, size_t height, size_t width, FrameHandler frameHandler, void *userData)
Definition: wge100lib.c:1908
#define PKT_STATUST_ERROR
Command could not be completed. See status_code for details.
Definition: ipcam_packet.h:570
uint32_t ser_no
Indicates the specific serial number of this unit from the flash.
Definition: ipcam_packet.h:235
#define PKT_STATUST_OK
Command completed successfully.
Definition: ipcam_packet.h:569
#define list_for_each_entry(pos, head, member)
Definition: list.h:252
#define PKTT_SENSORRD
Definition: ipcam_packet.h:118
void wge100CamListDelAll(IpCamList *ipCamList)
Definition: list.c:191
uint32_t ticks_lo
32 LSBs of system time base
Definition: ipcam_packet.h:613
#define IMAGER_LINENO_OVF
Flags this video packet as being an Overflow packet.
Definition: ipcam_packet.h:665
int wge100SensorSelect(const IpCamList *camInfo, uint8_t index, uint32_t reg)
Definition: wge100lib.c:1438
int wge100VidReceive(const char *ifName, uint16_t port, size_t height, size_t width, FrameHandler frameHandler, void *userData)
Definition: wge100lib.c:1889
char ip_str[16]
Definition: list.h:296
int wge100CamListInit(IpCamList *ipCamList)
Definition: list.c:50
IPAddress addr
Definition: ipcam_packet.h:80
#define PKTT_VIDSTART
Definition: ipcam_packet.h:111
uint32_t frame_number
Frame number as reported by Imager peripheral.
Definition: ipcam_packet.h:681
uint16_t vert_resolution
Number of video line packets per frame (not including EOF packet)
Definition: ipcam_packet.h:684
int wge100ReliableSensorWrite(const IpCamList *camInfo, uint8_t reg, uint16_t data, int *retries)
Definition: wge100lib.c:1252
uint32_t trig_state
Trigger state configuration.
Definition: ipcam_packet.h:401
uint32_t fw_version
Definition: list.h:291
uint16_t vertical
Number of video lines per frame.
Definition: ipcam_packet.h:521
NetHost receiver
Receiver Designation.
Definition: ipcam_packet.h:263
int wge100StopVid(const IpCamList *camInfo)
Definition: wge100lib.c:700
uint8_t mac[6]
Definition: list.h:294
#define WGE100_CAMINFO_LEN
Definition: list.h:272
uint16_t horiz_resolution
Number of 8-bit pixels per video line.
Definition: ipcam_packet.h:683
#define PKTT_FLASHWRITE
Definition: ipcam_packet.h:116
#define PKTT_ANNOUNCE
Definition: ipcam_packet.h:127
int wge100EthGetLocalMac(const char *ifName, struct sockaddr *macAddr)
Definition: host_netutil.c:154
#define IMAGER_LINENO_XOR
(Not an error) provides an XOR line for the frame (used only by the library)
Definition: ipcam_packet.h:674
uint32_t ticks_per_sec
Number of time base ticks that occur per second.
Definition: ipcam_packet.h:615
#define WG_MAGIC_NO
Definition: ipcam_packet.h:94
#define IMAGER_LINENO_ABORT
Flags this video packet as being an Abort packet.
Definition: ipcam_packet.h:668
uint32_t product_id
Camera Identification Section.
Definition: ipcam_packet.h:234
uint32_t mode
The mode number to select (range 0..9)
Definition: ipcam_packet.h:495
int wge100ImagerModeSelect(const IpCamList *camInfo, uint32_t mode)
Definition: wge100lib.c:1491
char camera_name[40]
The name assigned to this particular camera. Null terminated string.
Definition: ipcam_packet.h:631
#define PKTT_RECONFIG_FPGA
Definition: ipcam_packet.h:124
#define LINE_NUMBER_MASK
Definition: wge100lib.c:1593
int wge100SensorRead(const IpCamList *camInfo, uint8_t reg, uint16_t *data)
Definition: wge100lib.c:1378
#define ERR_TIMEOUT
Definition: wge100lib.h:115
int wge100ReconfigureFPGA(IpCamList *camInfo)
Definition: wge100lib.c:750
size_t missingLines
Definition: wge100lib.h:74
uint32_t magic_no
The Willow Garage Magic number (always WG_MAGIC_NO)
Definition: ipcam_packet.h:155
int wge100ReliableSensorRead(const IpCamList *camInfo, uint8_t reg, uint16_t *data, int *retries)
Definition: wge100lib.c:1349
char cam_name[CAMERA_NAME_LEN]
Definition: list.h:304
int wge100TriggerControl(const IpCamList *camInfo, uint32_t triggerType)
Definition: wge100lib.c:1135
#define IMAGER_LINENO_ERR
Flags this video packet as being a General Error packet.
Definition: ipcam_packet.h:662
#define PKTT_CONFIGURE
Definition: ipcam_packet.h:110
PacketGeneric hdr
Generic Command Packet Headers.
Definition: ipcam_packet.h:202
#define CONFIG_PRODUCT_ID
Definition: wge100lib.h:114
#define FLASH_MAX_PAGENO
Definition: ipcam_packet.h:59
#define CAMERA_NAME_LEN
Definition: ipcam_packet.h:64
int wge100ReliableFlashRead(const IpCamList *camInfo, uint32_t address, uint8_t *pageDataOut, int *retries)
Definition: wge100lib.c:906
int wge100FlashRead(const IpCamList *camInfo, uint32_t address, uint8_t *pageDataOut)
Definition: wge100lib.c:940
#define PKTT_FLASHDATA
Definition: ipcam_packet.h:130
int wge100SocketConnect(int s, const IPAddress *ip)
Definition: host_netutil.c:353
uint32_t address
Dataflash page address.
Definition: ipcam_packet.h:349
#define STD_REPLY_TIMEOUT
Amount of time in microseconds that the host should wait for packet replies.
Definition: wge100lib.c:50
#define IMAGER_LINENO_EOF
Flags this video packet as being an normal End Of Frame packet.
Definition: ipcam_packet.h:659
static int wge100DiscoverSend(const char *ifName, const char *ipAddress)
Definition: wge100lib.c:314
int wge100GetTimer(const IpCamList *camInfo, uint64_t *time_us)
Definition: wge100lib.c:832
uint32_t i2c_valid
Flags that indicate which &#39;i2c&#39; values were updated during the previous frame.
Definition: ipcam_packet.h:722
#define PKTT_IMGRSETRES
Definition: ipcam_packet.h:122
int wge100FlashWrite(const IpCamList *camInfo, uint32_t address, const uint8_t *pageDataIn)
Definition: wge100lib.c:1077
MACAddress mac
Camera Identification Section.
Definition: ipcam_packet.h:544
uint8_t * frameData
Definition: wge100lib.h:77
int(* FrameHandler)(wge100FrameInfo *frame_info, void *userData)
A FrameHandler function returns zero to continue to receive data, non-zero otherwise.
Definition: wge100lib.h:110
char ifName[128]
Definition: list.h:293
uint32_t serial
Definition: list.h:275
int wge100SendUDPBcast(int s, const char *ifName, const void *data, size_t dataSize)
Definition: host_netutil.c:464
uint16_t i2c[I2C_REGS_PER_FRAME]
Storage for I2C values read during the frame.
Definition: ipcam_packet.h:721
#define PKTT_DISCOVER
Definition: ipcam_packet.h:109
int wge100StartVid(const IpCamList *camInfo, const uint8_t mac[6], const char *ipAddress, uint16_t port)
Definition: wge100lib.c:638
int wge100ReliableFlashWrite(const IpCamList *camInfo, uint32_t address, const uint8_t *pageDataIn, int *retries)
Definition: wge100lib.c:1014
int wge100SensorWrite(const IpCamList *camInfo, uint8_t reg, uint16_t data)
Definition: wge100lib.c:1291
uint32_t fw_version
Definition: ipcam_packet.h:648
uint32_t ticks_hi
32 MSBs of system time base
Definition: ipcam_packet.h:612
uint32_t status_type
Type of status report (OK, Error, etc)
Definition: ipcam_packet.h:591
uint16_t horizontal
Number of 8-bit video pixels per image row.
Definition: ipcam_packet.h:520
struct timeval startTime
Definition: wge100lib.h:80
#define I2C_REGS_PER_FRAME
Number of I2C register to read during each video frame interval.
Definition: ipcam_packet.h:704
int wge100FindByUrl(const char *url, IpCamList *camera, unsigned wait_us, const char **errmsg)
Definition: wge100lib.c:94
#define PKTT_IMGRMODE
Definition: ipcam_packet.h:121
size_t width
Definition: wge100lib.h:68
uint32_t hw_version
Definition: list.h:283
UDPPort port
Definition: ipcam_packet.h:81
#define PKTT_TIMEREQ
Definition: ipcam_packet.h:114


wge100_camera
Author(s): Blaise Gassend, Patrick Mihelich, Eric MacIntosh, David Palchak
autogenerated on Mon Jun 10 2019 15:44:16