Revision: 6977
          http://playerstage.svn.sourceforge.net/playerstage/?rev=6977&view=rev
Author:   gbiggs
Date:     2008-08-25 00:58:33 +0000 (Mon, 25 Aug 2008)

Log Message:
-----------
Applied patch 2062373

Modified Paths:
--------------
    code/player/trunk/client_libs/libplayerc/dev_ranger.c
    code/player/trunk/client_libs/libplayerc++/actarrayproxy.cc
    code/player/trunk/client_libs/libplayerc++/audioproxy.cc
    code/player/trunk/client_libs/libplayerc++/cameraproxy.cc
    code/player/trunk/client_libs/libplayerc++/limbproxy.cc
    code/player/trunk/cmake/internal/FindOS.cmake
    code/player/trunk/cmake/internal/SearchForStuff.cmake
    code/player/trunk/server/drivers/blackboard/localbb/localbb.cpp
    code/player/trunk/server/drivers/mixed/mricp/src/Timer.cpp
    code/player/trunk/server/drivers/mixed/mricp/src/mricp_driver.cpp
    code/player/trunk/server/drivers/wsn/accel_calib.cc
    code/player/trunk/server/drivers/wsn/mica2.cc
    code/player/trunk/utils/logsplitter/logsplitter.c
    code/player/trunk/utils/playercam/playercam.c
    code/player/trunk/utils/playerv/pv_dev_actarray.c
    code/player/trunk/utils/playerv/pv_dev_gripper.c
    code/player/trunk/utils/playerv/pv_dev_vectormap.c

Modified: code/player/trunk/client_libs/libplayerc/dev_ranger.c
===================================================================
--- code/player/trunk/client_libs/libplayerc/dev_ranger.c       2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/client_libs/libplayerc/dev_ranger.c       2008-08-25 
00:58:33 UTC (rev 6977)
@@ -52,7 +52,7 @@
 {
   playerc_ranger_t *device;
 
-  device = malloc(sizeof(playerc_ranger_t));
+  device = (playerc_ranger_t*) malloc(sizeof(playerc_ranger_t));
   memset(device, 0, sizeof(playerc_ranger_t));
   playerc_device_init(&device->info, client, PLAYER_RANGER_CODE, index,
                       (playerc_putmsg_fn_t) playerc_ranger_putmsg);
@@ -98,6 +98,9 @@
 // Calculate bearings
 void playerc_ranger_calculate_bearings(playerc_ranger_t *device)
 {
+  double b;
+  uint32_t ii;
+
   device->bearings_count = device->ranges_count;
   if (device->bearings_count == 0 && device->bearings != NULL)
   {
@@ -113,8 +116,7 @@
       return;
     }
 
-    double b = device->min_angle;
-    uint32_t ii;
+    b = device->min_angle;
     for (ii = 0; ii < device->bearings_count; ii++)
     {
       device->bearings[ii] = b;
@@ -127,6 +129,9 @@
 // Calculate scan points
 void playerc_ranger_calculate_points(playerc_ranger_t *device)
 {
+  double b;
+  uint32_t ii;
+
   device->points_count = device->ranges_count;
   if (device->points_count == 0 && device->points != NULL)
   {
@@ -142,8 +147,7 @@
       return;
     }
 
-    double b = device->min_angle;
-    uint32_t ii;
+    b = device->min_angle;
     for (ii = 0; ii < device->points_count; ii++)
     {
       double r = device->ranges[ii];

Modified: code/player/trunk/client_libs/libplayerc++/actarrayproxy.cc
===================================================================
--- code/player/trunk/client_libs/libplayerc++/actarrayproxy.cc 2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/client_libs/libplayerc++/actarrayproxy.cc 2008-08-25 
00:58:33 UTC (rev 6977)
@@ -48,6 +48,7 @@
 #include <sstream>
 #include <iomanip>
 #include <vector>
+#include <iostream>
 
 #include "playerc++.h"
 #include "debug.h"
@@ -94,7 +95,7 @@
   player_actarray_actuatorgeom_t geom;
 
   int old_precision = os.precision(3);
-  std::_Ios_Fmtflags old_flags = os.flags();
+  std::ios::fmtflags old_flags = os.flags();
   os.setf(std::ios::fixed);
 
   os << a.GetCount () << " actuators:" << std::endl;

Modified: code/player/trunk/client_libs/libplayerc++/audioproxy.cc
===================================================================
--- code/player/trunk/client_libs/libplayerc++/audioproxy.cc    2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/client_libs/libplayerc++/audioproxy.cc    2008-08-25 
00:58:33 UTC (rev 6977)
@@ -47,6 +47,7 @@
 #include <cassert>
 #include <sstream>
 #include <iomanip>
+#include <iostream>
 
 #include "playerc++.h"
 #include "debug.h"
@@ -93,7 +94,7 @@
   player_audio_mixer_channel_t channel;
 
   int old_precision = os.precision(3);
-  std::_Ios_Fmtflags old_flags = os.flags();
+  std::ios::fmtflags old_flags = os.flags();
   os.setf(std::ios::fixed);
 
   int NumChannelDetails = a.GetMixerDetailsCount();

Modified: code/player/trunk/client_libs/libplayerc++/cameraproxy.cc
===================================================================
--- code/player/trunk/client_libs/libplayerc++/cameraproxy.cc   2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/client_libs/libplayerc++/cameraproxy.cc   2008-08-25 
00:58:33 UTC (rev 6977)
@@ -46,6 +46,9 @@
 #include <cassert>
 #include <sstream>
 #include <iomanip>
+#if __GNUC__ > 2
+  #include <locale>
+#endif
 
 #include "playerc++.h"
 #include "debug.h"
@@ -95,7 +98,9 @@
 CameraProxy::SaveFrame(const std::string aPrefix, uint32_t aWidth)
 {
   std::ostringstream filename;
+#if __GNUC__ > 2
   filename.imbue(std::locale(""));
+#endif
   filename.fill('0');
 
   filename << aPrefix << std::setw(aWidth) << mFrameNo++;

Modified: code/player/trunk/client_libs/libplayerc++/limbproxy.cc
===================================================================
--- code/player/trunk/client_libs/libplayerc++/limbproxy.cc     2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/client_libs/libplayerc++/limbproxy.cc     2008-08-25 
00:58:33 UTC (rev 6977)
@@ -47,6 +47,7 @@
 #include <cassert>
 #include <sstream>
 #include <iomanip>
+#include <iostream>
 
 #include "playerc++.h"
 #include "debug.h"
@@ -94,7 +95,7 @@
   player_limb_geom_req_t geom = a.GetGeom ();
 
   int old_precision = os.precision(3);
-  std::_Ios_Fmtflags old_flags = os.flags();
+  std::ios::fmtflags old_flags = os.flags();
   os.setf(std::ios::fixed);
 
   os << "Limb offset: " << geom.basePos.px << ", " << geom.basePos.py << ", " 
<< geom.basePos.pz << endl;

Modified: code/player/trunk/cmake/internal/FindOS.cmake
===================================================================
--- code/player/trunk/cmake/internal/FindOS.cmake       2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/cmake/internal/FindOS.cmake       2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -5,7 +5,7 @@
 # Nor *BSD
 STRING (REGEX MATCH "BSD" PLAYER_OS_BSD ${CMAKE_SYSTEM_NAME})
 # Or Solaris. I'm seeing a trend, here
-STRING (REGEX MATCH "Solaris" PLAYER_OS_SOLARIS ${CMAKE_SYSTEM_NAME})
+STRING (REGEX MATCH "SunOS" PLAYER_OS_SOLARIS ${CMAKE_SYSTEM_NAME})
 
 # Windows is easy (for once)
 IF (WIN32)

Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake
===================================================================
--- code/player/trunk/cmake/internal/SearchForStuff.cmake       2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/cmake/internal/SearchForStuff.cmake       2008-08-25 
00:58:33 UTC (rev 6977)
@@ -37,6 +37,7 @@
 CHECK_INCLUDE_FILES (stdint.h HAVE_STDINT_H)
 CHECK_INCLUDE_FILES (strings.h HAVE_STRINGS_H)
 CHECK_INCLUDE_FILES (dns_sd.h HAVE_DNS_SD)
+CHECK_INCLUDE_FILES (sys/filio.h HAVE_SYS_FILIO_H)
 IF (HAVE_DNS_SD)
     CHECK_LIBRARY_EXISTS (dns_sd DNSServiceRefDeallocate 
"${PLAYER_EXTRA_LIB_DIRS}" HAVE_DNS_SD)
 ENDIF (HAVE_DNS_SD)

Modified: code/player/trunk/server/drivers/blackboard/localbb/localbb.cpp
===================================================================
--- code/player/trunk/server/drivers/blackboard/localbb/localbb.cpp     
2008-08-22 18:19:44 UTC (rev 6976)
+++ code/player/trunk/server/drivers/blackboard/localbb/localbb.cpp     
2008-08-25 00:58:33 UTC (rev 6977)
@@ -66,13 +66,15 @@
 /** @} */
 
 #include <sys/types.h> // required by Darwin
-#include <stdlib.h>
 #include <libplayercore/playercore.h>
 #include <libplayercore/error.h>
 #include <vector>
 #include <map>
-#include <strings.h>
 #include <iostream>
+#include <cstdlib>
+#include <cstddef>
+#include <string>
+#include <cstring>
 
 bool operator ==(const player_devaddr_t &a, const player_devaddr_t &b);
 bool operator <(const player_devaddr_t &a, const player_devaddr_t &b);
@@ -108,9 +110,9 @@
   BlackBoardEntry() { key = ""; group = ""; }
 
   /** Entry label */
-  string key;
+  std::string key;
   /** Secondary identifier. */
-  string group;
+  std::string group;
   /** Entry data */
   EntryData data;
 } BlackBoardEntry;
@@ -154,8 +156,8 @@
   BlackBoardEntry result;
   result.data.type = entry.type;
   result.data.subtype = entry.subtype;
-  result.key = string(entry.key);
-  result.group = string(entry.group);
+  result.key = std::string(entry.key);
+  result.group = std::string(entry.group);
   result.data.data_count = entry.data_count;
   result.data.data = new uint8_t[result.data.data_count];
   memcpy(result.data.data, entry.data, result.data.data_count);
@@ -258,26 +260,26 @@
                 * @param group Second identifier.
                 * @param resp_queue Player response queue of the subscriber.
                 */
-               BlackBoardEntry SubscribeKey(const string &key, const string 
&group, const QueuePointer &resp_queue, const player_devaddr_t addr);
+               BlackBoardEntry SubscribeKey(const std::string &key, const 
std::string &group, const QueuePointer &resp_queue, const player_devaddr_t 
addr);
                /** @brief Remove the key and queue combination from the 
listeners hash-map.
                 * @param key Entry key.
                 * @param group Second identifier.
                 * @param qp Player response queue of the unsubscriber.
                 * @return Blackboard entry containing the value of the key and 
group.
                 */
-               void UnsubscribeKey(const string &key, const string &group, 
const QueuePointer &qp);
+               void UnsubscribeKey(const std::string &key, const std::string 
&group, const QueuePointer &qp);
                /** @brief Add a group to the group listeners hash-map and 
return all entries of that group
                 * @param group Entry gruop
                 * @param qp resp_queue Player response queue of the subscriber
                 * @return Vector of blackboard entries of that group
                 */
-               vector<BlackBoardEntry> SubscribeGroup(const string &group, 
const QueuePointer &qp, const player_devaddr_t addr);
+               vector<BlackBoardEntry> SubscribeGroup(const std::string 
&group, const QueuePointer &qp, const player_devaddr_t addr);
                /**
                 * @brief Remove the group from the group listeners hash-map.
                 * @param group Entry group
                 * @param qp Player response queue of the unsubscriber
                 */
-               void UnsubscribeGroup(const string &group, const QueuePointer 
&qp);
+               void UnsubscribeGroup(const std::string &group, const 
QueuePointer &qp);
 
                /** @brief Set the entry in the entries hashmap. *
                * @param entry BlackBoardEntry that must be put in the hashmap.
@@ -295,16 +297,16 @@
                * map<group, map<key, entry> >
                */
 
-               map<string, map<string, BlackBoardEntry> > entries;
+               map<std::string, map<std::string, BlackBoardEntry> > entries;
                /** Map of labels to listening queues.
                * map<group, map<key, vector<device queue> > >
                */
-               map<string, map<string, vector<QueuePointer> > > listeners;
+               map<std::string, map<std::string, vector<QueuePointer> > > 
listeners;
 
                /** Map of groups to queues subscribed to groups.
                * map<group, vector<device queue> >
                */
-               map<string, vector<QueuePointer> > group_listeners;
+               map<std::string, vector<QueuePointer> > group_listeners;
 
                /** Map of queues to devices. Used to remove unneeded queues 
when a device is unsubscribed. */
                map<player_devaddr_t, QueuePointer> subscribed_devices;
@@ -314,10 +316,10 @@
 int LocalBB::Unsubscribe(player_devaddr_t addr)
 {
        QueuePointer &qp = subscribed_devices[addr];
-       for (map<string, map<string, vector<QueuePointer> > >::iterator itr = 
listeners.begin(); itr != listeners.end(); itr++)
+       for (map<std::string, map<std::string, vector<QueuePointer> > 
>::iterator itr = listeners.begin(); itr != listeners.end(); itr++)
        {
-               map<string, vector<QueuePointer> > &keys = (*itr).second;
-               for (map<string, vector<QueuePointer> >::iterator jtr = 
keys.begin(); jtr != keys.end(); jtr++)
+               map<std::string, vector<QueuePointer> > &keys = (*itr).second;
+               for (map<std::string, vector<QueuePointer> >::iterator jtr = 
keys.begin(); jtr != keys.end(); jtr++)
                {
                        vector<QueuePointer> &qps = (*jtr).second;
                        vector<vector<QueuePointer>::iterator> remove_list;
@@ -335,7 +337,7 @@
                }
        }
 
-       for (map<string, vector<QueuePointer> >::iterator itr = 
group_listeners.begin(); itr != group_listeners.end(); itr++)
+       for (map<std::string, vector<QueuePointer> >::iterator itr = 
group_listeners.begin(); itr != group_listeners.end(); itr++)
        {
                vector<QueuePointer> &qps = (*itr).second;
                vector<vector<QueuePointer>::iterator> remove_list;
@@ -497,7 +499,7 @@
 
        // Retrieve the entry for the key
        player_blackboard_entry_t *request = 
reinterpret_cast<player_blackboard_entry_t*>(data);
-       BlackBoardEntry current_value = 
entries[string(request->group)][string(request->key)];
+       BlackBoardEntry current_value = 
entries[std::string(request->group)][std::string(request->key)];
 
        // Convert the entry
        player_blackboard_entry_t response = 
ToPlayerBlackBoardEntry(current_value);
@@ -685,7 +687,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Add a device to the listener list for a key. Return the current value of 
the entry.
-BlackBoardEntry LocalBB::SubscribeKey(const string &key, const string &group, 
const QueuePointer &resp_queue, const player_devaddr_t addr)
+BlackBoardEntry LocalBB::SubscribeKey(const std::string &key, const 
std::string &group, const QueuePointer &resp_queue, const player_devaddr_t addr)
 {
        listeners[group][key].push_back(resp_queue);
        subscribed_devices[addr] = resp_queue;
@@ -700,7 +702,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Remove a device from the listener list for a key.
-void LocalBB::UnsubscribeKey(const string &key, const string &group, const 
QueuePointer &qp)
+void LocalBB::UnsubscribeKey(const std::string &key, const std::string &group, 
const QueuePointer &qp)
 {
        vector<QueuePointer> &devices = listeners[group][key];
 
@@ -716,16 +718,16 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Add a device to the group listener map. Return vector of entries for that 
group.
-vector<BlackBoardEntry> LocalBB::SubscribeGroup(const string &group, const 
QueuePointer &qp, const player_devaddr_t addr)
+vector<BlackBoardEntry> LocalBB::SubscribeGroup(const std::string &group, 
const QueuePointer &qp, const player_devaddr_t addr)
 {
        group_listeners[group].push_back(qp);
        subscribed_devices[addr] = qp;
 
        vector<BlackBoardEntry> group_entries;
        //map<group, map<key, entry> >
-       map<string, BlackBoardEntry> &entry_map = entries[group];
+       map<std::string, BlackBoardEntry> &entry_map = entries[group];
 
-       for (map<string, BlackBoardEntry>::iterator itr = entry_map.begin(); 
itr != entry_map.end(); itr++)
+       for (map<std::string, BlackBoardEntry>::iterator itr = 
entry_map.begin(); itr != entry_map.end(); itr++)
        {
                BlackBoardEntry current_value = (*itr).second;
                if (current_value.key == "")
@@ -743,7 +745,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Remove a device from the group listener map
-void LocalBB::UnsubscribeGroup(const string &group, const QueuePointer &qp)
+void LocalBB::UnsubscribeGroup(const std::string &group, const QueuePointer 
&qp)
 {
        vector<QueuePointer> &devices = group_listeners[group];
 

Modified: code/player/trunk/server/drivers/mixed/mricp/src/Timer.cpp
===================================================================
--- code/player/trunk/server/drivers/mixed/mricp/src/Timer.cpp  2008-08-22 
18:19:44 UTC (rev 6976)
+++ code/player/trunk/server/drivers/mixed/mricp/src/Timer.cpp  2008-08-25 
00:58:33 UTC (rev 6977)
@@ -1,4 +1,6 @@
 #include "Timer.h"
+#include <ctime>
+#include <cstddef>
 
 Timer::Timer()
 {
@@ -7,8 +9,8 @@
 double Timer::TimeElapsed() // return in usec
 {
        gettimeofday(&end_time,NULL);
-       time_diff = ((double) end_time.tv_sec*1e6   + (double)end_time.tv_usec) 
-  
-                   ((double) start_time.tv_sec*1e6 + 
(double)start_time.tv_usec);
+       time_diff = ((double) end_time.tv_sec*1000000 + 
(double)end_time.tv_usec) -
+                   ((double) start_time.tv_sec*1000000 + 
(double)start_time.tv_usec);
        return  time_diff;
 }
 Timer::~Timer()
@@ -20,7 +22,17 @@
 }
 void Timer::Synch(double period)
 {
+       struct timespec ts;
+       int us;
+
        double time_elapsed = this->TimeElapsed();
-       if( time_elapsed < period*1e3)
-               usleep((int)(period*1e3 -time_elapsed)); 
+       if( time_elapsed < period*1000)
+               usleep((int)(period*1000 -time_elapsed));
+       if (time_elapsed < (period*1000))
+       {
+               us = static_cast<int>(period*1000-time_elapsed);
+               ts.tv_sec = us/1000000;
+               ts.tv_nsec = (us%1000000)*1000;
+               nanosleep(&ts, NULL);
+       }
 }

Modified: code/player/trunk/server/drivers/mixed/mricp/src/mricp_driver.cpp
===================================================================
--- code/player/trunk/server/drivers/mixed/mricp/src/mricp_driver.cpp   
2008-08-22 18:19:44 UTC (rev 6976)
+++ code/player/trunk/server/drivers/mixed/mricp/src/mricp_driver.cpp   
2008-08-25 00:58:33 UTC (rev 6977)
@@ -36,22 +36,24 @@
 #include <sys/time.h>
 #include <fcntl.h>
 #include <termios.h>
-#include <stdio.h>
-#include <strings.h>
+#include <cstdio>
 #include <unistd.h>
-#include <stdlib.h>
-#include <errno.h>
-#include <string.h>
+#include <cstdlib>
+#include <cstddef>
+#include <cerrno>
+#include <cstring>
+#include <string>
 #include <pthread.h>
-#include <math.h>
+#include <cmath>
 #include <fstream>
 #include <iostream>
-#include <signal.h>
+#include <csignal>
+#include <vector>
 #include <netinet/in.h>
 // Player includes
 #include <libplayercore/playercore.h>
 
-#include <assert.h>
+#include <cassert>
 #include "icp.h"
 #include "map.h"
 #include "lasermodel.h"

Modified: code/player/trunk/server/drivers/wsn/accel_calib.cc
===================================================================
--- code/player/trunk/server/drivers/wsn/accel_calib.cc 2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/server/drivers/wsn/accel_calib.cc 2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -383,13 +383,11 @@
 NodeCalibrationValues Accel_Calib::FindNodeValues (unsigned int nodeID)
 {
     NodeCalibrationValues n;
+    NCV::iterator it;
 
-    unsigned int i = 0;
-
-    for (i = 0; i < ncv.size (); i++)
+    for (it = ncv.begin (); it != ncv.end (); it++)
     {
-        n = ncv.at (i);
-
+        n = *it;
         if (n.node_id == nodeID)
             break;
     }

Modified: code/player/trunk/server/drivers/wsn/mica2.cc
===================================================================
--- code/player/trunk/server/drivers/wsn/mica2.cc       2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/server/drivers/wsn/mica2.cc       2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -883,15 +883,13 @@
 NodeCalibrationValues Mica2::FindNodeValues (unsigned int nodeID)
 {
     NodeCalibrationValues n;
+    NCV::iterator it;
 
-    unsigned int i = 0;
-
-    for (i = 0; i < ncv.size (); i++)
+    for (it = ncv.begin (); it != ncv.end (); it++)
     {
-       n = ncv.at (i);
-
-       if (n.node_id == nodeID)
-           break;
+        n = *it;
+        if (n.node_id == nodeID)
+            break;
     }
 
     return n;

Modified: code/player/trunk/utils/logsplitter/logsplitter.c
===================================================================
--- code/player/trunk/utils/logsplitter/logsplitter.c   2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/utils/logsplitter/logsplitter.c   2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -19,8 +19,8 @@
  * CVS: $Id$
  */
 /*
- Desc  : Splits log files into smaller chunks, based on the difference between 
-         consecutive timestamp entries. A bit ugly, but it works. There's room 
+ Desc  : Splits log files into smaller chunks, based on the difference between
+         consecutive timestamp entries. A bit ugly, but it works. There's room
         for optimization, so feel free.
  Author: Radu Bogdan Rusu
  Date  : 20th of September, 2006
@@ -35,7 +35,7 @@
 #include <sys/stat.h>
 
 // Splits a logfile and returns the new file handle
-FILE 
+FILE
 *copySplitData (FILE *input, double t2, long before)
 {
     char data[1024];
@@ -48,10 +48,10 @@
 
     // Save current position in file
     long currentPos = ftell (input);
-    
+
     // Seek to the beginning of the file
     fseek (input, 0L, SEEK_SET);
-    
+
     // Read the first entry
     while (!feof (input))
     {
@@ -75,7 +75,7 @@
     {
         output = fopen (fileName, "w+");
         printf ("I: Creating... %s\n", fileName);
-       
+
        // Copy the relevant data
        while (!feof (input))
        {
@@ -84,10 +84,10 @@
                break;
            fputs (data, output);
        }
-        
+
        // Seek back in the source file
        fseek (input, currentPos - strlen (data), SEEK_SET);
-    
+
        // Close output file
        fclose (output);
     }
@@ -97,18 +97,18 @@
        // Seek back in the source file
        fseek (input, currentPos - before, SEEK_SET);
     }
-    
+
     // Create a new file and copy the remainings there
     sprintf (fileName, "%lf-split.log", t2);
     if (stat (fileName, &fbuf) != 0)
     {
        rest = fopen (fileName, "w+");
-       printf ("I: Creating... %s\n", fileName);       
+       printf ("I: Creating... %s\n", fileName);
        while (1)
        {
            fgets (data, 1024, input);
            lastdatalen = strlen (data);
-           if (feof (input)) 
+           if (feof (input))
                break;
            fputs (data, rest);
        }
@@ -118,7 +118,7 @@
        // Truncate the remainings from the source file
         ftruncate (fileno (input), currentPos - before);
        fclose (input);
-       
+
        return rest;
     }
     else
@@ -141,7 +141,7 @@
     float min_timedifference;
     struct stat fbuf;
     struct stat ftempbuf;
-    
+
     // We need 2 parameters
     if (argc != 3)
     {
@@ -150,13 +150,13 @@
                 "USAGE:  logsplitter [min_time_difference_in_seconds] 
[FILE]\n\n");
        return -1;
     }
-    
+
     // Get the minimum time difference between two consecutive timestamps
     min_timedifference = atof (argv[1]);
     base_filename = argv[2];
-    
+
     printf ("I: Minimum time difference is: %f seconds.\n", 
min_timedifference);
-    
+
     // Open file for reading
     fd = fopen (base_filename, "r+");
     if (!fd)
@@ -175,17 +175,17 @@
        printf ("E: Cannot create a temporary file! Aborting...\n");
        return -1;
     }
-    
+
     // Copy the content of our logfile to that temporary file
     while (1)
     {
        fgets (buf, 1024, fd);
-        if (feof (fd)) 
+        if (feof (fd))
            break;
        fputs (buf, tempfd);
     }
     fflush (tempfd);
-    
+
     // Close the original logfile
     fclose (fd);
 
@@ -196,7 +196,7 @@
        printf ("E: The temporary file differs than the original log file by 
%ld bytes! Aborting...",
            fbuf.st_size - ftempbuf.st_size);
     }
-    
+
     // Get an initial reading
     rewind (tempfd);
     while (!feof (tempfd))
@@ -223,13 +223,17 @@
            sscanf (buf, "%lf", &t2);
 
        after  = ftell (tempfd);
-       
+
        // Verify if we need a break
        if ((fabs (t2 - t1) > min_timedifference) && (after - before > 0))
        {
-           time_t t = (time_t)t1;
-           ctime_r (&t, btime);
-           printf ("I: Break (%f) needed after T = %f -> %s", t2 - t1, t1, 
btime);
+        time_t t = (time_t)t1;
+#if defined (__SVR4) && defined (__sun)
+        ctime_r (&t, btime, sizeof (btime));
+#else
+        ctime_r (&t, btime);
+#endif
+        printf ("I: Break (%f) needed after T = %f -> %s", t2 - t1, t1, btime);
 
            tempfd = copySplitData (tempfd, t2, after - before);
            if (ftell (tempfd) == 0)
@@ -241,6 +245,6 @@
 
     // Close file
     fclose (tempfd);
-    
+
     return 0;
 }

Modified: code/player/trunk/utils/playercam/playercam.c
===================================================================
--- code/player/trunk/utils/playercam/playercam.c       2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/utils/playercam/playercam.c       2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -190,9 +190,10 @@
   GdkPixbuf *blobbuf= NULL;
   GdkGC         *gc = NULL;
   GtkWidget *drawing_area = GTK_WIDGET(data);
-  gc = 
GTK_WIDGET(drawing_area)->style->fg_gc[GTK_WIDGET_STATE(GTK_WIDGET(drawing_area))];
   uint16_t i;
 
+  gc = 
GTK_WIDGET(drawing_area)->style->fg_gc[GTK_WIDGET_STATE(GTK_WIDGET(drawing_area))];
+
   player_update();
 
   if (g_blob_count > 0)
@@ -447,7 +448,7 @@
   assert(g_width>0);
   assert(g_height>0);
 
-  playerc_client_datamode(g_client,PLAYER_DATAMODE_PULL); 
+  playerc_client_datamode(g_client,PLAYER_DATAMODE_PULL);
   playerc_client_set_replace_rule(g_client,-1,-1,PLAYER_MSGTYPE_DATA,-1,1);
 }
 
@@ -462,17 +463,17 @@
     {
       // Decompress the image if necessary
       playerc_camera_decompress(g_camera);
+      assert(allocated_size > g_camera->image_count*3);
       // figure out the colorspace
       switch (g_camera->format)
       {
-        assert(allocated_size > g_camera->image_count*3);
         case PLAYER_CAMERA_FORMAT_MONO8:
           // we should try to use the alpha layer,
           // but for now we need to change
           // the image data
           for (i=0;i<g_camera->image_count;++i)
           {
-        
+
             memcpy(g_img+i*3, g_camera->image+i, 3);
           }
           break;
@@ -482,8 +483,8 @@
           // Transform to MONO8
           for (i = 0; i < g_camera->image_count; i++, j+=2)
           {
-            g_img[i*3+1] = g_img[i*3+2] = g_img[i*3+3] = 
-                 ((unsigned char)(g_camera->image[j]) << 8) + 
+            g_img[i*3+1] = g_img[i*3+2] = g_img[i*3+3] =
+                 ((unsigned char)(g_camera->image[j]) << 8) +
                  (unsigned char)(g_camera->image[j+1]);
           }
           break;

Modified: code/player/trunk/utils/playerv/pv_dev_actarray.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_actarray.c   2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/utils/playerv/pv_dev_actarray.c   2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -1,4 +1,4 @@
-/* 
+/*
  *  PlayerViewer
  *  Copyright (C) Andrew Howard 2002
  *
@@ -46,7 +46,7 @@
   char section[64];
   char label[64];
   actarray_t *actarray;
-  
+
   actarray = malloc(sizeof(actarray_t));
   actarray->datatime = 0;
   actarray->drivername = strdup(drivername);
@@ -66,7 +66,7 @@
   actarray->menu = rtk_menu_create_sub(mainwnd->device_menu, label);
   actarray->subscribe_item = rtk_menuitem_create(actarray->menu, "Subscribe", 
1);
   actarray->command_item = rtk_menuitem_create(actarray->menu, "Command", 1);
-  
+
   // Set the initial menu state
   rtk_menuitem_check(actarray->subscribe_item, 
actarray->proxy->info.subscribed);
 
@@ -75,7 +75,7 @@
   actarray->actuator_fig_cmd = NULL;
   actarray->lastvalue = NULL;
   actarray->mainwnd = mainwnd;
-  
+
   return actarray;
 }
 
@@ -198,8 +198,8 @@
   double min, max;
   double ax, ay, bx, by;
   double fx, fd;
-
   int ii;
+  rtk_fig_t *fig;
 
   actarray_allocate(actarray, actarray->proxy->actuators_count);
 
@@ -217,7 +217,7 @@
     if (value > max) value = max;
     if (value < min) value = min;
     value = 2*(value-min)/(max-min) -1;
-    rtk_fig_t * fig = actarray->actuator_fig[ii];
+    fig = actarray->actuator_fig[ii];
     rtk_fig_show(fig, 1);
     rtk_fig_clear(fig);
     rtk_fig_origin(actarray->actuator_fig[ii], ARRAY_SPACING*ii 
+ARRAY_X_OFFSET, 0, 0);

Modified: code/player/trunk/utils/playerv/pv_dev_gripper.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_gripper.c    2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/utils/playerv/pv_dev_gripper.c    2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -105,6 +105,10 @@
 // Update a gripper device
 void gripper_update(gripper_t *gripper)
 {
+  double gripper_length, gripper_width;
+  double paddle_center, paddle_length, paddle_width, paddle_pos;
+  double ibbx, obbx, bby;
+  double led_dx;
   int i;
 
   // Update the device subscription
@@ -151,12 +155,12 @@
 
        // draw paddles
 
-       double gripper_length = gripper->proxy->outer_size.sw;
-       double gripper_width = gripper->proxy->outer_size.sl;
+       gripper_length = gripper->proxy->outer_size.sw;
+       gripper_width = gripper->proxy->outer_size.sl;
 
-       double paddle_center = gripper_length * (1.0/6.0);
-       double paddle_length = gripper_length * (2.0/3.0);
-       double paddle_width = gripper_width * 0.15;
+       paddle_center = gripper_length * (1.0/6.0);
+       paddle_length = gripper_length * (2.0/3.0);
+       paddle_width = gripper_width * 0.15;
 
        rtk_fig_color_rgb32( gripper->grip_fig, GRIPPER_COLOR_FILL );
        rtk_fig_rectangle( gripper->grip_fig,
@@ -174,7 +178,7 @@
 
        if( gripper->proxy->state == PLAYER_GRIPPER_STATE_OPEN )
          {
-           double paddle_pos = gripper_width/2.0 - paddle_width/2.0;
+           paddle_pos = gripper_width/2.0 - paddle_width/2.0;
 
            rtk_fig_color_rgb32( gripper->grip_fig, GRIPPER_COLOR_FILL );
            rtk_fig_rectangle(gripper->grip_fig,
@@ -196,7 +200,7 @@
 
        if( gripper->proxy->state == PLAYER_GRIPPER_STATE_CLOSED )
          {
-           double paddle_pos = paddle_width/2.0;
+           paddle_pos = paddle_width/2.0;
 
            rtk_fig_color_rgb32( gripper->grip_fig, GRIPPER_COLOR_FILL );
            rtk_fig_rectangle(gripper->grip_fig,
@@ -227,14 +231,14 @@
 
 
        // different x location for each beam
-       double ibbx =  paddle_center - 0.3*paddle_length;
-       double obbx =  paddle_center + 0.3*paddle_length;
+       ibbx =  paddle_center - 0.3*paddle_length;
+       obbx =  paddle_center + 0.3*paddle_length;
 
        // common y position
-       double bby = (gripper->proxy->state == PLAYER_GRIPPER_STATE_OPEN) ? 
gripper_width/2.0 - paddle_width: 0;
+       bby = (gripper->proxy->state == PLAYER_GRIPPER_STATE_OPEN) ? 
gripper_width/2.0 - paddle_width: 0;
 
        // size of the paddle indicator lights
-       double led_dx = paddle_width/2.0;
+       led_dx = paddle_width/2.0;
 
        if( gripper->proxy->beams & 0x00000001 )
          {

Modified: code/player/trunk/utils/playerv/pv_dev_vectormap.c
===================================================================
--- code/player/trunk/utils/playerv/pv_dev_vectormap.c  2008-08-22 18:19:44 UTC 
(rev 6976)
+++ code/player/trunk/utils/playerv/pv_dev_vectormap.c  2008-08-25 00:58:33 UTC 
(rev 6977)
@@ -1,4 +1,4 @@
-/* 
+/*
  *  PlayerViewer
  *  Copyright (C) Andrew Howard 2002
  *
@@ -32,7 +32,7 @@
 // Update the map configuration
 void vectormap_update_config(vectormap_t *map);
 
-// Draw the map 
+// Draw the map
 void vectormap_draw(vectormap_t *map);
 
 // Draw a single map feature
@@ -46,7 +46,7 @@
   char label[64];
   char section[64];
   vectormap_t *map;
-  
+
   map = malloc(sizeof(vectormap_t));
   map->proxy = playerc_vectormap_create(client, index);
   map->drivername = strdup(drivername);
@@ -163,12 +163,13 @@
 {
   unsigned ii, jj;
   GEOSGeom feature;
+  uint32_t colour = 0xFF0000;
+  double xCenter, yCenter;
 
   rtk_fig_show(map->fig, 1);
   rtk_fig_clear(map->fig);
 
   // draw map data
-  uint32_t colour = 0xFF0000;
   for (ii = 0;  ii < map->proxy->layers_count; ++ii)
   {
     // get a different colour for each layer the quick way, will duplicate 
after 6 layers
@@ -186,8 +187,8 @@
 
   // draw map extent
   rtk_fig_color_rgb32( map->fig, 0xFF0000 );
-  double xCenter = map->proxy->extent.x1 - (map->proxy->extent.x1 - 
map->proxy->extent.x0)/2;
-  double yCenter = map->proxy->extent.y1 - (map->proxy->extent.y1 - 
map->proxy->extent.y0)/2;
+  xCenter = map->proxy->extent.x1 - (map->proxy->extent.x1 - 
map->proxy->extent.x0)/2;
+  yCenter = map->proxy->extent.y1 - (map->proxy->extent.y1 - 
map->proxy->extent.y0)/2;
 
   rtk_fig_rectangle(
                     map->fig,
@@ -210,7 +211,8 @@
   unsigned numcoords;
   unsigned ii;
   double x,y,x2,y2;
-  switch (GEOSGeomTypeId(geom)) 
+
+  switch (GEOSGeomTypeId(geom))
   {
     case GEOS_POINT:
       seq = GEOSGeom_getCoordSeq(geom);


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

-------------------------------------------------------------------------
This SF.Net email is sponsored by the Moblin Your Move Developer's challenge
Build the coolest Linux based applications with Moblin SDK & win great prizes
Grand prize is a trip for two to an Open Source event anywhere in the world
http://moblin-contest.org/redirect.php?banner_id=100&url=/
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to