Revision: 6599
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6599&view=rev
Author:   thjc
Date:     2008-06-16 17:49:32 -0700 (Mon, 16 Jun 2008)

Log Message:
-----------
merged file watcher changes from 2-1 (6501,6539,6540)

Modified Paths:
--------------
    code/player/trunk/libplayercore/CMakeLists.txt
    code/player/trunk/libplayercore/driver.cc
    code/player/trunk/libplayercore/driver.h
    code/player/trunk/libplayercore/globals.cc
    code/player/trunk/libplayercore/globals.h
    code/player/trunk/libplayercore/playercore.h
    code/player/trunk/libplayertcp/playertcp.cc
    code/player/trunk/libplayertcp/playerudp.cc
    code/player/trunk/server/drivers/blobfinder/acts/acts.cc
    code/player/trunk/server/drivers/opaque/tcpstream.cc
    code/player/trunk/server/server.cc

Added Paths:
-----------
    code/player/trunk/libplayercore/Makefile.am
    code/player/trunk/libplayercore/filewatcher.cc
    code/player/trunk/libplayercore/filewatcher.h

Modified: code/player/trunk/libplayercore/CMakeLists.txt
===================================================================
--- code/player/trunk/libplayercore/CMakeLists.txt      2008-06-17 00:27:13 UTC 
(rev 6598)
+++ code/player/trunk/libplayercore/CMakeLists.txt      2008-06-17 00:49:32 UTC 
(rev 6599)
@@ -55,6 +55,7 @@
              drivertable.cc
              devicetable.cc
              configfile.cc
+             filewatcher.cc
              message.cc
              wallclocktime.cc
              plugins.cc
@@ -104,6 +105,7 @@
                                    driver.h
                                    drivertable.h
                                    error.h
+                                   filewatcher.h
                                    globals.h
                                    interface_util.h
                                    message.h

Added: code/player/trunk/libplayercore/Makefile.am
===================================================================
--- code/player/trunk/libplayercore/Makefile.am                         (rev 0)
+++ code/player/trunk/libplayercore/Makefile.am 2008-06-17 00:49:32 UTC (rev 
6599)
@@ -0,0 +1,70 @@
+AM_CPPFLAGS = -g -Wall -D PLAYER_INSTALL_PREFIX="\"@[EMAIL PROTECTED]"" 
-I$(top_srcdir)
+
+# create the pkg-config entry for the server headers
+pkgconfigdir = $(libdir)/pkgconfig
+pkgconfig_DATA = playercore.pc playererror.pc playerutils.pc
+
+dist_bin_SCRIPTS = playerinterfacegen.py
+
+EXTRA_DIST = playercore.pc.in playererror.pc.in playerutils.pc.in 
interfaces/ADDING_INTERFACES $(shell find $(srcdir)/interfaces -name "*.def")
+
+BUILT_SOURCES = playerconfig.h player_interfaces.h interface_table.c
+CLEANFILES = playercore.pc playererror.pc playerutils.pc
+DISTCLEANFIELS = $BUILT_SOURCES 
+
+lib_LTLIBRARIES = libplayererror.la libplayerutils.la libplayercore.la
+
+libplayercore_la_SOURCES = driver.cc driver.h \
+                          device.cc device.h \
+                          drivertable.h drivertable.cc \
+                          devicetable.h devicetable.cc \
+                          configfile.cc configfile.h \
+                          playercommon.h player.h playerconfig.h.in \
+                          message.h message.cc \
+                          filewatcher.cc filewatcher.h \
+                          wallclocktime.cc wallclocktime.h playertime.h \
+                          plugins.cc plugins.h \
+                          globals.cc globals.h \
+                          property.cpp property.h
+libplayercore_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir) 
$(top_builddir)/libplayercore/libplayererror.la 
$(top_builddir)/libplayercore/libplayerutils.la
+libplayercore_la_DEPENDENCIES = 
$(top_builddir)/libplayercore/libplayererror.la 
$(top_builddir)/libplayercore/libplayerutils.la 
$(top_builddir)/libplayercore/player_interfaces.h
+
+libplayererror_la_SOURCES = error.h error.c
+libplayererror_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir)
+
+libplayerutils_la_SOURCES = interface_util.c interface_util.h \
+                            addr_util.c addr_util.h 
+libplayerutils_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir)
+libplayerutils_la_DEPENDENCIES = interface_table.c
+
+
+coreincludedir = 
$(includedir)/player-$(PLAYER_MAJOR_VERSION).$(PLAYER_MINOR_VERSION)/libplayercore
+coreinclude_HEADERS = configfile.h \
+                      device.h \
+                      devicetable.h \
+                      driver.h \
+                      drivertable.h \
+                      filewatcher.h \
+                      globals.h \
+                      interface_util.h \
+                      message.h \
+                      player.h \
+                      playercommon.h \
+                      playerconfig.h \
+                      playercore.h \
+                      playertime.h \
+                      plugins.h \
+                      wallclocktime.h \
+                      error.h \
+                      addr_util.h \
+                      property.h \
+                      player_interfaces.h
+                      
+player_interfaces.h: $(srcdir)/interfaces/* playerinterfacegen.py
+       python $(srcdir)/playerinterfacegen.py > $(builddir)/player_interfaces.h
+#      if ! ./playerinterfacegen.py > player_interfaces.h; then rm 
player_interfaces.h; fi
+
+interface_table.c: $(srcdir)/interfaces/* playerinterfacegen.py
+       python $(srcdir)/playerinterfacegen.py --utils > 
$(top_builddir)/libplayercore/interface_table.c
+#      if ! ./playerinterfacegen.py --utils > interface_table.c; then rm 
interface_table.c; fi
+

Modified: code/player/trunk/libplayercore/driver.cc
===================================================================
--- code/player/trunk/libplayercore/driver.cc   2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayercore/driver.cc   2008-06-17 00:49:32 UTC (rev 
6599)
@@ -61,6 +61,7 @@
 #include <libplayercore/devicetable.h>
 #include <libplayercore/configfile.h>
 #include <libplayercore/globals.h>
+#include <libplayercore/filewatcher.h>
 #include <libplayercore/property.h>
 #include <libplayercore/interface_util.h>
 
@@ -226,10 +227,10 @@
 }
 
 void
-Driver::Publish(player_devaddr_t addr, 
-                uint8_t type, 
+Driver::Publish(player_devaddr_t addr,
+                uint8_t type,
                 uint8_t subtype,
-                void* src, 
+                void* src,
                 size_t deprecated,
                 double* timestamp,
                 bool copy)
@@ -302,6 +303,19 @@
   return( shutdownResult );
 }
 
+/** @brief Wake up the driver if the specified event occurs on the file 
descriptor */
+int Driver::AddFileWatch(int fd, bool ReadWatch , bool WriteWatch , bool 
ExceptWatch )
+{
+  return 
fileWatcher->AddFileWatch(fd,InQueue,ReadWatch,WriteWatch,ExceptWatch);
+}
+
+/** @brief Remove a previously added watch, call with the same arguments as 
when adding the watch */
+int Driver::RemoveFileWatch(int fd, bool ReadWatch , bool WriteWatch , bool 
ExceptWatch )
+{
+  return 
fileWatcher->RemoveFileWatch(fd,InQueue,ReadWatch,WriteWatch,ExceptWatch);
+}
+
+
 /* start a thread that will invoke Main() */
 void
 Driver::StartThread(void)

Modified: code/player/trunk/libplayercore/driver.h
===================================================================
--- code/player/trunk/libplayercore/driver.h    2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayercore/driver.h    2008-06-17 00:49:32 UTC (rev 
6599)
@@ -146,7 +146,7 @@
     @returns 0 on success, non-zero otherwise. */
     int AddInterface(player_devaddr_t *addr, ConfigFile * cf, int section, int 
code, char * key = NULL);
 
-    
+
     /** @brief Set/reset error code */
     void SetError(int code) {this->error = code;}
 
@@ -154,13 +154,20 @@
 
     Call this method to block until a new message arrives on
     Driver::InQueue.  This method will return true immediately if at least
-    one message is already waiting. 
-    
+    one message is already waiting.
+
     If TimeOut is set to a positive value this method will return false if the
     timeout occurs before and update is recieved.
     */
     bool Wait(double TimeOut=0.0) { return this->InQueue->Wait(); }
 
+    /** @brief Wake up the driver if the specified event occurs on the file 
descriptor */
+    int AddFileWatch(int fd, bool ReadWatch = true, bool WriteWatch = false, 
bool ExceptWatch = true);
+
+    /** @brief Remove a previously added watch, call with the same arguments 
as when adding the watch */
+    int RemoveFileWatch(int fd, bool ReadWatch = true, bool WriteWatch = 
false, bool ExceptWatch = true);
+
+
   public:
     /** @brief The driver's thread.
 
@@ -203,10 +210,10 @@
                  bool copy=true);
 
      /** @brief Publish a message via one of this driver's interfaces.
-     
+
      This form of Publish will assemble the message header for you.
      The message is broadcast to all interested parties
-     
+
      @param addr The origin address
      @param type The message type
      @param subtype The message subtype
@@ -215,23 +222,23 @@
      @param timestamp Timestamp for the message body (if NULL, then the
      current time will be filled in)
      @param copy if set to false the data will be claimed and the caller 
should no longer use or free it */
-     virtual void Publish(player_devaddr_t addr, 
-                  uint8_t type, 
+     virtual void Publish(player_devaddr_t addr,
+                  uint8_t type,
                   uint8_t subtype,
-                  void* src=NULL, 
+                  void* src=NULL,
                   size_t deprecated=0,
                   double* timestamp=NULL,
                   bool copy=true);
- 
- 
 
+
+
     /** @brief Publish a message via one of this driver's interfaces.
 
     Use this form of Publish if you already have the message header
     assembled and have a target queue to send to.
     @param queue the target queue.
     @param hdr The message header
-    @param src The message body 
+    @param src The message body
     @param copy if set to false the data will be claimed and the caller should 
no longer use or free it */
     virtual void Publish(QueuePointer &queue,
                  player_msghdr_t* hdr,
@@ -243,8 +250,8 @@
     Use this form of Publish if you already have the message header
     assembled and wish to broadcast the message to all subscribed parties.
     @param hdr The message header
-    @param src The message body 
-    @param copy if set to false the data will be claimed and the caller should 
no longer use or free it */ 
+    @param src The message body
+    @param copy if set to false the data will be claimed and the caller should 
no longer use or free it */
     virtual void Publish(player_msghdr_t* hdr,
                  void* src,
                  bool copy = true);
@@ -321,15 +328,15 @@
     subscriptions to the driver; a driver MAY override them, but
     usually won't. This alternative form includes the clients queue
     so you can map future requests and unsubscriptions to a specific queue.
-    
+
     If this methods returns a value other than 1 then the other form of 
subscribe wont be called
 
     @param queue The queue of the subscribing client
     @param addr Address of the device to subscribe to (the driver may
     have more than one interface).
     @returns Returns 0 on success, -ve on error and 1 for unimplemented. */
-    virtual int Subscribe(QueuePointer &queue, player_devaddr_t addr) {return 
1;};    
-    
+    virtual int Subscribe(QueuePointer &queue, player_devaddr_t addr) {return 
1;};
+
     /** @brief Unsubscribe from this driver.
 
     The Subscribe() and Unsubscribe() methods are used to control
@@ -347,7 +354,7 @@
     subscriptions to the driver; a driver MAY override them, but
     usually won't.This alternative form includes the clients queue
     so you can map future requests and unsubscriptions to a specific queue.
-    
+
     If this methods returns a value other than 1 then the other form of 
subscribe wont be called
 
     @param queue The queue of the subscribing client
@@ -355,7 +362,7 @@
     have more than one interface).
     @returns Returns 0 on success. */
     virtual int Unsubscribe(QueuePointer &queue, player_devaddr_t addr) 
{return 1;};
-    
+
     /** @brief Initialize the driver.
 
     This function is called with the first client subscribes; it MUST
@@ -447,7 +454,6 @@
     @param section Configuration file section that may define the property 
value
     @return True if the property was registered, false otherwise */
     virtual bool RegisterProperty(Property *prop, ConfigFile* cf, int section);
-
 };
 
 

Added: code/player/trunk/libplayercore/filewatcher.cc
===================================================================
--- code/player/trunk/libplayercore/filewatcher.cc                              
(rev 0)
+++ code/player/trunk/libplayercore/filewatcher.cc      2008-06-17 00:49:32 UTC 
(rev 6599)
@@ -0,0 +1,192 @@
+/*
+ * FileWatcher.cc
+ *
+ *  Created on: 10/06/2008
+ *      Author: tcollett
+ */
+
+#include <libplayercore/filewatcher.h>
+#include <libplayercore/message.h>
+#include <libplayercore/error.h>
+#include <sys/time.h>
+#include <stdlib.h>
+#include <assert.h>
+#include <error.h>
+#include <math.h>
+#include <string.h>
+
+FileWatcher::FileWatcher()
+{
+       WatchedFilesArraySize = INITIAL_WATCHED_FILES_ARRAY_SIZE;
+       WatchedFilesArrayCount = 0;
+       WatchedFiles = reinterpret_cast<struct fd_driver_pair *> 
(calloc(WatchedFilesArraySize,sizeof(WatchedFiles[0])));
+       assert(WatchedFiles);
+       pthread_mutex_init(&this->lock,NULL);
+
+}
+
+FileWatcher::~FileWatcher()
+{
+       free(WatchedFiles);
+}
+
+void FileWatcher::Lock()
+{
+  pthread_mutex_lock(&lock);
+}
+
+void FileWatcher::Unlock()
+{
+  pthread_mutex_unlock(&lock);
+}
+
+
+int FileWatcher::Wait(double Timeout)
+{
+       Lock();
+       if (WatchedFilesArrayCount == 0)
+       {
+               Unlock();
+               return 0;
+       }
+
+       // intialise our FD sets for the select call
+       fd_set ReadFds,WriteFds,ExceptFds;
+       FD_ZERO(&ReadFds);
+       FD_ZERO(&WriteFds);
+       FD_ZERO(&ExceptFds);
+
+       int maxfd = 0;
+
+       for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii)
+       {
+               if (WatchedFiles[ii].fd >= 0)
+               {
+                       if (WatchedFiles[ii].fd > maxfd)
+                               maxfd = WatchedFiles[ii].fd;
+                       if (WatchedFiles[ii].Read)
+                               FD_SET(WatchedFiles[ii].fd,&ReadFds);
+                       if (WatchedFiles[ii].Write)
+                               FD_SET(WatchedFiles[ii].fd,&WriteFds);
+                       if (WatchedFiles[ii].Except)
+                               FD_SET(WatchedFiles[ii].fd,&ExceptFds);
+               }
+       }
+
+       struct timeval t;
+       t.tv_sec = static_cast<int> (floor(Timeout));
+       t.tv_usec = static_cast<int> ((Timeout - static_cast<int> 
(floor(Timeout))) * 1e6);
+       Unlock();
+
+       int ret = select (maxfd+1,&ReadFds,&WriteFds,&ExceptFds,&t);
+
+       if (ret < 0)
+       {
+               PLAYER_ERROR2("Select called failed in File Watcher: %d 
%s",errno,strerror(errno));
+               return ret;
+       }
+
+       int queueless_count = 0;
+
+       Lock();
+       for (unsigned int ii = 0; ii < WatchedFilesArrayCount && 
static_cast<int> (ii) < maxfd; ++ii)
+       {
+               int fd = WatchedFiles[ii].fd;
+               QueuePointer &q = WatchedFiles[ii].queue;
+               if (fd > 0 && fd <= maxfd)
+               {
+                       if ((WatchedFiles[ii].Read && FD_ISSET(fd,&ReadFds)) ||
+                                       (WatchedFiles[ii].Write && 
FD_ISSET(fd,&WriteFds)) ||
+                                       (WatchedFiles[ii].Except && 
FD_ISSET(fd,&ExceptFds)))
+                       {
+                               if (q != NULL)
+                               {
+                                       q->DataAvailable();
+                               }
+                               else
+                                       queueless_count++;
+
+                       }
+               }
+       }
+       Unlock();
+
+       return queueless_count;
+}
+
+int FileWatcher::AddFileWatch(int fd, bool WatchRead, bool WatchWrite, bool 
WatchExcept)
+{
+       QueuePointer q;
+       return AddFileWatch(fd, q,WatchRead,WatchWrite,WatchExcept);
+}
+
+
+int FileWatcher::AddFileWatch(int fd, QueuePointer & queue, bool WatchRead, 
bool WatchWrite, bool WatchExcept)
+{
+       Lock();
+       fprintf(stderr,"Added file watch %d \n",fd);
+       // find the first available file descriptor
+       struct fd_driver_pair *next_entry = NULL;
+       if (WatchedFilesArrayCount < WatchedFilesArraySize)
+       {
+               next_entry = &WatchedFiles[WatchedFilesArrayCount];
+               WatchedFilesArrayCount++;
+       }
+       else
+       {
+               // first see if there is an empty spot in the list
+               for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii)
+               {
+                       if (WatchedFiles[ii].fd < 0)
+                       {
+                               next_entry = &WatchedFiles[ii];
+                               break;
+                       }
+               }
+               if (next_entry == NULL)
+               {
+                       // otherwise we allocate some more room for the array
+                       WatchedFilesArraySize*=2;
+                       WatchedFiles = reinterpret_cast<struct fd_driver_pair 
*> (realloc(WatchedFiles,sizeof(WatchedFiles[0])*WatchedFilesArraySize));
+                       next_entry = &WatchedFiles[WatchedFilesArrayCount];
+
+               }
+       }
+
+       next_entry->fd = fd;
+       next_entry->queue = queue;
+       next_entry->Read = WatchRead;
+       next_entry->Write = WatchWrite;
+       next_entry->Except = WatchExcept;
+       Unlock();
+       return 0;
+}
+
+int FileWatcher::RemoveFileWatch(int fd, bool WatchRead, bool WatchWrite, bool 
WatchExcept)
+{
+       QueuePointer q;
+       return RemoveFileWatch(fd, q,WatchRead,WatchWrite,WatchExcept);
+}
+
+
+int FileWatcher::RemoveFileWatch(int fd, QueuePointer &queue, bool WatchRead, 
bool WatchWrite, bool WatchExcept)
+{
+       Lock();
+       // this finds the first matching entry and removes it. It only removes 
one entry so call remove for every add
+       for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii)
+       {
+               if (WatchedFiles[ii].fd == fd &&
+                               WatchedFiles[ii].queue == queue &&
+                               WatchedFiles[ii].Read == WatchRead &&
+                               WatchedFiles[ii].Write == WatchWrite &&
+                               WatchedFiles[ii].Except == WatchExcept)
+               {
+                       WatchedFiles[ii].fd = -1;
+                       Unlock();
+                       return 0;
+               }
+       }
+       Unlock();
+       return -1;
+}
+

Added: code/player/trunk/libplayercore/filewatcher.h
===================================================================
--- code/player/trunk/libplayercore/filewatcher.h                               
(rev 0)
+++ code/player/trunk/libplayercore/filewatcher.h       2008-06-17 00:49:32 UTC 
(rev 6599)
@@ -0,0 +1,56 @@
+/*
+ * filewatcher.h
+ *
+ *  Created on: 10/06/2008
+ *      Author: tcollett
+ */
+
+#ifndef FILEWATCHER_H_
+#define FILEWATCHER_H_
+
+#include <sys/select.h>
+#include <sys/types.h>
+#include <stdlib.h>
+#include <pthread.h>
+#include <libplayercore/message.h>
+
+class MessageQueue;
+
+struct fd_driver_pair
+{
+       int fd;
+       QueuePointer queue;
+       bool Read;
+       bool Write;
+       bool Except;
+};
+
+const size_t INITIAL_WATCHED_FILES_ARRAY_SIZE = 32;
+
+class FileWatcher
+{
+public:
+       FileWatcher();
+       virtual ~FileWatcher();
+
+       int Wait(double Timeout = 0);
+       int AddFileWatch(int fd, QueuePointer & queue, bool WatchRead = true, 
bool WatchWrite = false, bool WatchExcept = true);
+       int RemoveFileWatch(int fd, QueuePointer & queue, bool WatchRead = 
true, bool WatchWrite = false, bool WatchExcept = true);
+       int AddFileWatch(int fd, bool WatchRead = true, bool WatchWrite = 
false, bool WatchExcept = true);
+       int RemoveFileWatch(int fd, bool WatchRead = true, bool WatchWrite = 
false, bool WatchExcept = true);
+
+private:
+       struct fd_driver_pair * WatchedFiles;
+       size_t WatchedFilesArraySize;
+       size_t WatchedFilesArrayCount;
+
+    /** @brief Lock access to watcher internals. */
+    virtual void Lock(void);
+    /** @brief Unlock access to watcher internals. */
+    virtual void Unlock(void);
+    /// Used to lock access to Data.
+    pthread_mutex_t lock;
+
+};
+
+#endif /* FILEWATCHER_H_ */

Modified: code/player/trunk/libplayercore/globals.cc
===================================================================
--- code/player/trunk/libplayercore/globals.cc  2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayercore/globals.cc  2008-06-17 00:49:32 UTC (rev 
6599)
@@ -47,6 +47,7 @@
 
 #include <libplayercore/devicetable.h>
 #include <libplayercore/drivertable.h>
+#include <libplayercore/filewatcher.h>
 #include <libplayercore/playertime.h>
 #include <libplayercore/wallclocktime.h>
 
@@ -60,11 +61,14 @@
 // this table holds all the currently *available* drivers
 DriverTable* driverTable;
 
-// the global PlayerTime object has a method 
+// the global PlayerTime object has a method
 //   int GetTime(struct timeval*)
 // which everyone must use to get the current time
 PlayerTime* GlobalTime;
 
+// global class for watching for changes in files and sockets
+FileWatcher* fileWatcher;
+
 char playerversion[32];
 
 bool player_quit;
@@ -84,6 +88,7 @@
   deviceTable = new DeviceTable();
   driverTable = new DriverTable();
   GlobalTime = new WallclockTime();
+  fileWatcher = new FileWatcher();
   strncpy(playerversion, PLAYER_VERSION, sizeof(playerversion));
   player_quit = false;
   player_quiet_startup = false;
@@ -95,12 +100,10 @@
 void
 player_globals_fini()
 {
-  if(deviceTable)
-    delete deviceTable;
-  if(driverTable)
-    delete driverTable;
-  if(GlobalTime)
-    delete GlobalTime;
+  delete deviceTable;
+  delete driverTable;
+  delete GlobalTime;
+  delete fileWatcher;
 #if HAVE_PLAYERSD
   if(globalSD)
     player_sd_fini(globalSD);

Modified: code/player/trunk/libplayercore/globals.h
===================================================================
--- code/player/trunk/libplayercore/globals.h   2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayercore/globals.h   2008-06-17 00:49:32 UTC (rev 
6599)
@@ -44,11 +44,13 @@
 class DeviceTable;
 class PlayerTime;
 class DriverTable;
+class FileWatcher;
 struct player_sd;
 
 extern DeviceTable* deviceTable;
 extern PlayerTime* GlobalTime;
 extern DriverTable* driverTable;
+extern FileWatcher* fileWatcher;
 extern char playerversion[];
 extern bool player_quit;
 extern bool player_quiet_startup;

Modified: code/player/trunk/libplayercore/playercore.h
===================================================================
--- code/player/trunk/libplayercore/playercore.h        2008-06-17 00:27:13 UTC 
(rev 6598)
+++ code/player/trunk/libplayercore/playercore.h        2008-06-17 00:49:32 UTC 
(rev 6599)
@@ -46,6 +46,7 @@
 #include <libplayercore/driver.h>
 #include <libplayercore/drivertable.h>
 #include <libplayercore/error.h>
+#include <libplayercore/filewatcher.h>
 #include <libplayercore/globals.h>
 #include <libplayercore/interface_util.h>
 #include <libplayercore/message.h>

Modified: code/player/trunk/libplayertcp/playertcp.cc
===================================================================
--- code/player/trunk/libplayertcp/playertcp.cc 2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayertcp/playertcp.cc 2008-06-17 00:49:32 UTC (rev 
6599)
@@ -187,6 +187,9 @@
     // set up for later use of poll() to accept() connections on this port
     this->listen_ufds[i].fd = this->listeners[i].fd;
     this->listen_ufds[i].events = POLLIN;
+
+    // set up for later use by global file watcher
+    fileWatcher->AddFileWatch(this->listeners[i].fd);
   }
 
   return(0);
@@ -246,6 +249,10 @@
   this->client_ufds[j].fd = this->clients[j].fd;
   this->client_ufds[j].events = POLLIN;
 
+  // set up for later use by global file watcher
+  fileWatcher->AddFileWatch(this->client_ufds[j].fd);
+
+
   // Create an outgoing queue for this client
   this->clients[j].queue =
           QueuePointer(true,PLAYER_MSGQUEUE_DEFAULT_MAXLEN);
@@ -388,6 +395,8 @@
   free(this->clients[cli].dev_subs);
   if(close(this->clients[cli].fd) < 0)
     PLAYER_WARN1("close() failed: %s", strerror(errno));
+  fileWatcher->RemoveFileWatch(this->clients[cli].fd);
+
   this->clients[cli].fd = -1;
   this->clients[cli].valid = 0;
   this->clients[cli].queue = QueuePointer();

Modified: code/player/trunk/libplayertcp/playerudp.cc
===================================================================
--- code/player/trunk/libplayertcp/playerudp.cc 2008-06-17 00:27:13 UTC (rev 
6598)
+++ code/player/trunk/libplayertcp/playerudp.cc 2008-06-17 00:49:32 UTC (rev 
6599)
@@ -174,6 +174,10 @@
     // set up for later use of poll() to accept() connections on this port
     this->listen_ufds[i].fd = this->listeners[i].fd;
     this->listen_ufds[i].events = POLLIN;
+
+    // set up for later use by global file watcher
+    fileWatcher->AddFileWatch(this->listeners[i].fd);
+
   }
 
   return(0);
@@ -269,6 +273,7 @@
     }
   }
   free(this->clients[cli].dev_subs);
+  fileWatcher->RemoveFileWatch(this->clients[cli].fd);
   this->clients[cli].fd = -1;
   this->clients[cli].valid = 0;
   // FIXME

Modified: code/player/trunk/server/drivers/blobfinder/acts/acts.cc
===================================================================
--- code/player/trunk/server/drivers/blobfinder/acts/acts.cc    2008-06-17 
00:27:13 UTC (rev 6598)
+++ code/player/trunk/server/drivers/blobfinder/acts/acts.cc    2008-06-17 
00:49:32 UTC (rev 6599)
@@ -430,7 +430,7 @@
 
 // returns the enum representation of the given version string, or
 // -1 on failure to match.
-acts_version_t Acts::version_string_to_enum(char* versionstr)
+acts_version_t Acts::version_string_to_enum(const char* versionstr)
 {
   if(!strcmp(versionstr,ACTS_VERSION_1_0_STRING))
     return(ACTS_VERSION_1_0);
@@ -497,103 +497,121 @@
   // build the argument list, based on version
   switch(acts_version)
   {
-    case ACTS_VERSION_1_0:
-      acts_args[i++] = "-t";
+    // these are needed as execv expects a const array of char *'s not an 
array of const char *'s
+    static char dash_d[3] = "-d";
+    static char dash_i[3] = "-i";
+    static char dash_n[3] = "-n";
+    static char dash_p[3] = "-p";
+    static char dash_s[3] = "-s";
+    static char dash_t[3] = "-t";
+    static char dash_w[3] = "-w";
+    static char dash_x[3] = "-x";
+
+    static char dash_B[3] = "-B";
+    static char dash_C[3] = "-C";
+    static char dash_G[3] = "-G";
+    static char dash_H[3] = "-H";
+    static char dash_R[3] = "-R";
+    static char dash_V[3] = "-V";
+    static char dash_W[3] = "-W";
+
+  case ACTS_VERSION_1_0:
+      acts_args[i++] = dash_t;
       acts_args[i++] = configfilepath;
       if(strlen(portnumstring))
       {
-        acts_args[i++] = "-s";
+        acts_args[i++] = dash_s;
         acts_args[i++] = portnumstring;
       }
       if(strlen(devicepath))
       {
-        acts_args[i++] = "-d";
+        acts_args[i++] = dash_d;
         acts_args[i++] = devicepath;
       }
       break;
     case ACTS_VERSION_1_2:
-      acts_args[i++] = "-t";
+      acts_args[i++] = dash_t;
       acts_args[i++] = configfilepath;
       if(strlen(portnumstring))
       {
-        acts_args[i++] = "-p";
+        acts_args[i++] = dash_p;
         acts_args[i++] = portnumstring;
       }
       if(strlen(devicepath))
       {
-        acts_args[i++] = "-d";
+        acts_args[i++] = dash_d;
         acts_args[i++] = devicepath;
       }
       if(strlen(contrast))
       {
-        acts_args[i++] = "-C";
+        acts_args[i++] = dash_C;
         acts_args[i++] = contrast;
       }
       if(strlen(brightness))
       {
-        acts_args[i++] = "-B";
+        acts_args[i++] = dash_B;
         acts_args[i++] = brightness;
       }
-      acts_args[i++] = "-W";
+      acts_args[i++] = dash_W;
       acts_args[i++] = widthstring;
-      acts_args[i++] = "-H";
+      acts_args[i++] = dash_H;
       acts_args[i++] = heightstring;
       break;
     case ACTS_VERSION_2_0:
-      acts_args[i++] = "-t";
+      acts_args[i++] = dash_t;
       acts_args[i++] = configfilepath;
       if(strlen(minarea))
       {
-        acts_args[i++] = "-w";
+        acts_args[i++] = dash_w;
         acts_args[i++] = minarea;
       }
       if(strlen(portnumstring))
       {
-        acts_args[i++] = "-p";
+        acts_args[i++] = dash_p;
         acts_args[i++] = portnumstring;
       }
       if(strlen(fps))
       {
-        acts_args[i++] = "-R";
+        acts_args[i++] = dash_R;
         acts_args[i++] = fps;
       }
       if(strlen(drivertype))
       {
-        acts_args[i++] = "-G";
+        acts_args[i++] = dash_G;
         acts_args[i++] = drivertype;
       }
       if(invertp > 0)
-        acts_args[i++] = "-i";
+        acts_args[i++] = dash_i;
       if(strlen(devicepath))
       {
-        acts_args[i++] = "-d";
+        acts_args[i++] = dash_d;
         acts_args[i++] = devicepath;
       }
       if(strlen(channel))
       {
-        acts_args[i++] = "-n";
+        acts_args[i++] = dash_n;
         acts_args[i++] = channel;
       }
       if(strlen(norm))
       {
-        acts_args[i++] = "-V";
+        acts_args[i++] = dash_V;
         acts_args[i++] = norm;
       }
       if(pxc200p > 0)
-        acts_args[i++] = "-x";
+        acts_args[i++] = dash_x;
       if(strlen(brightness))
       {
-        acts_args[i++] = "-B";
+        acts_args[i++] = dash_B;
         acts_args[i++] = brightness;
       }
       if(strlen(contrast))
       {
-        acts_args[i++] = "-C";
+        acts_args[i++] = dash_C;
         acts_args[i++] = contrast;
       }
-      acts_args[i++] = "-W";
+      acts_args[i++] = dash_W;
       acts_args[i++] = widthstring;
-      acts_args[i++] = "-H";
+      acts_args[i++] = dash_H;
       acts_args[i++] = heightstring;
       break;
     case ACTS_VERSION_UNKNOWN:

Modified: code/player/trunk/server/drivers/opaque/tcpstream.cc
===================================================================
--- code/player/trunk/server/drivers/opaque/tcpstream.cc        2008-06-17 
00:27:13 UTC (rev 6598)
+++ code/player/trunk/server/drivers/opaque/tcpstream.cc        2008-06-17 
00:49:32 UTC (rev 6599)
@@ -112,22 +112,10 @@
 #include <libplayercore/playercore.h>
 
 #define DEFAULT_TCP_OPAQUE_BUFFER_SIZE 4096
-#define DEFAULT_TCP_OPAQUE_IP "10.99.10.6"
+#define DEFAULT_TCP_OPAQUE_IP "127.0.0.1"
 #define DEFAULT_TCP_OPAQUE_PORT 4002
 
 
////////////////////////////////////////////////////////////////////////////////
-// Device codes
-
-#define STX     0x02
-#define ACK     0xA0
-#define NACK    0x92
-#define CRC16_GEN_POL 0x8005
-
-////////////////////////////////////////////////////////////////////////////////
-// Error macros
-#define RETURN_ERROR(erc, m) {PLAYER_ERROR(m); return erc;}
-
-////////////////////////////////////////////////////////////////////////////////
 // The class for the driver
 class TCPStream : public Driver
 {
@@ -166,13 +154,7 @@
          int sock;
 
     uint8_t * rx_buffer;
-    //unsigned int rx_buffer_size;
 
-    struct termios oldtio;
-
-    // opaque device file descriptor
-    //int opaque_fd;
-
     // Properties
     IntProperty buffer_size;
     StringProperty ip;
@@ -314,8 +296,7 @@
   // The main loop; interact with the device here
   for(;;)
   {
-    // test if we are supposed to cancel
-    pthread_testcancel();
+    Wait(1);
 
     // Process incoming messages.  TCPStream::ProcessMessage() is
     // called on each message.
@@ -323,17 +304,14 @@
 
     if (connected)
     {
-       // Reads the data from the tcp server and then publishes it
-       ReadData();
+      // Reads the data from the tcp server and then publishes it
+      ReadData();
     }
     else
     {
-       PLAYER_MSG0(2, "TCP reconnecting");
-       OpenTerm();
+      PLAYER_MSG0(2, "TCP reconnecting");
+      OpenTerm();
     }
-
-    // Sleep (you might, for example, block on a read() instead)
-    usleep(1000);
   }
 }
 
@@ -371,7 +349,9 @@
 //
 int TCPStream::CloseTerm()
 {
+  RemoveFileWatch(sock);
   close(sock);
+
   connected = false;
   return 0;
 }

Modified: code/player/trunk/server/server.cc
===================================================================
--- code/player/trunk/server/server.cc  2008-06-17 00:27:13 UTC (rev 6598)
+++ code/player/trunk/server/server.cc  2008-06-17 00:49:32 UTC (rev 6599)
@@ -2,8 +2,8 @@
  *  Player - One Hell of a Robot Server
  *  Copyright (C) 2005 -
  *     Brian Gerkey
- *                      
  *
+ *
  *  This program is free software; you can redistribute it and/or modify
  *  it under the terms of the GNU General Public License as published by
  *  the Free Software Foundation; either version 2 of the License, or
@@ -109,7 +109,7 @@
 void PrintVersion();
 void PrintCopyrightMsg();
 void PrintUsage();
-int ParseArgs(int* port, int* debuglevel, 
+int ParseArgs(int* port, int* debuglevel,
               char** cfgfilename, int* gz_serverid,
               int argc, char** argv);
 void Quit(int signum);
@@ -145,7 +145,7 @@
     PLAYER_ERROR1("signal() failed: %s", strerror(errno));
     exit(-1);
   }
-  
+
   player_globals_init();
   player_register_drivers();
   playerxdr_ftable_init();
@@ -293,6 +293,9 @@
 
   while(!player_quit)
   {
+    // wait until something other than driver requested watches happens
+    fileWatcher->Wait();
+
     if(ptcp->Accept(0) < 0)
     {
       PLAYER_ERROR("failed while accepting new TCP connections");
@@ -363,7 +366,7 @@
   fprintf(stderr,"* Player comes with ABSOLUTELY NO WARRANTY.  This is free 
software, and you\n* are welcome to redistribute it under certain conditions; 
see COPYING\n* for details.\n\n");
 }
 
-void 
+void
 PrintUsage()
 {
   int maxlen=66;
@@ -394,13 +397,13 @@
 }
 
 
-int 
+int
 ParseArgs(int* port, int* debuglevel, char** cfgfilename, int* gz_serverid,
           int argc, char** argv)
 {
   int ch;
   const char* optflags = "d:p:hq";
-  
+
   // Get letter options
   while((ch = getopt(argc, argv, optflags)) != -1)
   {
@@ -417,7 +420,7 @@
         break;
       case '?':
       case ':':
-      case 'h':        
+      case 'h':
       default:
         return(-1);
     }
@@ -425,7 +428,7 @@
 
   if(optind >= argc)
     return(-1);
-  
+
   *cfgfilename = argv[optind];
 
   return(0);


This was sent by the SourceForge.net collaborative development platform, the 
world's largest Open Source development site.

-------------------------------------------------------------------------
Check out the new SourceForge.net Marketplace.
It's the best place to buy or sell services for
just about anything Open Source.
http://sourceforge.net/services/buy/index.php
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to