Update of /cvsroot/playerstage/code/player/client_libs/libplayerc
In directory 
sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv9713/client_libs/libplayerc

Modified Files:
      Tag: b_thjc_dynamic_arrays
        dev_actarray.c dev_aio.c dev_blobfinder.c dev_graphics2d.c 
        dev_graphics3d.c dev_localize.c dev_map.c dev_pointcloud3d.c 
        dev_rfid.c dev_simulation.c dev_speech.c 
        dev_speech_recognition.c playerc.h 
Log Message:
static array sizes removed from player
client library updated to use dynamic arrays


Index: dev_blobfinder.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_blobfinder.c,v
retrieving revision 1.13
retrieving revision 1.13.2.1
diff -C2 -d -r1.13 -r1.13.2.1
*** dev_blobfinder.c    27 Apr 2006 02:36:58 -0000      1.13
--- dev_blobfinder.c    10 Sep 2007 04:11:00 -0000      1.13.2.1
***************
*** 77,80 ****
--- 77,81 ----
  {
    playerc_device_term(&device->info);
+   free(device->blobs);
    free(device);
  }
***************
*** 109,114 ****
        
        // threshold the number of blobs to avoid overunning the array
!       device->blobs_count = MIN( data->blobs_count, 
PLAYERC_BLOBFINDER_MAX_BLOBS );
! 
        memcpy(device->blobs, data->blobs, sizeof 
(player_blobfinder_blob_t)*device->blobs_count);
  
--- 110,115 ----
        
        // threshold the number of blobs to avoid overunning the array
!       device->blobs_count =data->blobs_count;
!       device->blobs = realloc(device->blobs, device->blobs_count * 
sizeof(device->blobs[0]));
        memcpy(device->blobs, data->blobs, sizeof 
(player_blobfinder_blob_t)*device->blobs_count);
  

Index: dev_localize.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_localize.c,v
retrieving revision 1.16
retrieving revision 1.16.4.1
diff -C2 -d -r1.16 -r1.16.4.1
*** dev_localize.c      26 Jan 2006 13:31:11 -0000      1.16
--- dev_localize.c      10 Sep 2007 04:11:00 -0000      1.16.4.1
***************
*** 75,81 ****
  void playerc_localize_destroy(playerc_localize_t *device)
  {
-   if (device->map_cells)
-     free(device->map_cells);
    playerc_device_term(&device->info);
    free(device);
    return;
--- 75,82 ----
  void playerc_localize_destroy(playerc_localize_t *device)
  {
    playerc_device_term(&device->info);
+   free(device->map_cells);
+   free(device->hypoths);
+   free(device->particles);
    free(device);
    return;
***************
*** 105,120 ****
    device->pending_count = data->pending_count;
    device->pending_time = data->pending_time;
    for (i = 0; i < data->hypoths_count; i++)
    {
-     //device->hypoths[i].weight = data->hypoths[i].alpha;
- 
      device->hypoths[i] = data->hypoths[i];
- /*    device->hypoths[i].mean[1] = data->hypoths[i].mean.py;
-     device->hypoths[i].mean[2] = data->hypoths[i].mean.pa;
-     memset(device->hypoths[i].cov, 0, sizeof(double)*9);
-     for (k = 0; k < 3; k++)
-       device->hypoths[i].cov[k] = data->hypoths[i].cov[k];*/
    }
-   device->hypoth_count = data->hypoths_count;
    
    return;
--- 106,115 ----
    device->pending_count = data->pending_count;
    device->pending_time = data->pending_time;
+   device->hypoth_count = data->hypoths_count;
+   device->hypoths = 
realloc(device->hypoths,device->hypoth_count*sizeof(device->hypoths[0]));
    for (i = 0; i < data->hypoths_count; i++)
    {
      device->hypoths[i] = data->hypoths[i];
    }
    
    return;
***************
*** 169,182 ****
  
    device->num_particles = req.particles_count;
  
    for(i=0;i<device->num_particles;i++)
    {
-     if(i >= PLAYER_LOCALIZE_PARTICLES_MAX)
-     {
-       device->num_particles = i;
-       PLAYERC_WARN("too many particles");
-       break;
-     }
- 
      device->particles[i].pose[0] = req.particles[i].pose.px;
      device->particles[i].pose[1] = req.particles[i].pose.py;
--- 164,171 ----
  
    device->num_particles = req.particles_count;
+   device->particles = 
realloc(device->particles,req.particles_count*sizeof(device->particles[0]));
  
    for(i=0;i<device->num_particles;i++)
    {
      device->particles[i].pose[0] = req.particles[i].pose.px;
      device->particles[i].pose[1] = req.particles[i].pose.py;

Index: dev_speech_recognition.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_speech_recognition.c,v
retrieving revision 1.3
retrieving revision 1.3.2.1
diff -C2 -d -r1.3 -r1.3.2.1
*** dev_speech_recognition.c    9 Jun 2007 02:59:12 -0000       1.3
--- dev_speech_recognition.c    10 Sep 2007 04:11:00 -0000      1.3.2.1
***************
*** 24,27 ****
--- 24,29 ----
  {
    playerc_device_term(&device->info);
+   free(device->rawText);
+   free(device->words);
    free(device);
    return;
***************
*** 42,91 ****
  void playerc_speech_recognition_putmsg(playerc_speechrecognition_t *device, 
player_msghdr_t *hdr, player_speech_recognition_data_t *buffer, size_t len)
  {
! //   memset(device->words,0,30*20);
! //   player_speech_recognition_data_t *data = 
(player_speech_recognition_data_t*)buffer;
! // 
! //   if((hdr->type == PLAYER_MSGTYPE_DATA) && (hdr->subtype == 
PLAYER_SPEECH_RECOGNITION_DATA_STRING ))
! //   {
! //     char * str1;
! //     int i;
! //     device->wordCount = 0;
! // //    printf("data->text %s\n",data->text);
! // 
! //     for (str1 = strtok((*data).text, " ") ; str1 != NULL ; str1 = 
strtok(NULL, " ") )
! //     {
! //       for (i=0;i<strlen(str1);i++)
! //       {
! // //        printf("str1[%d]=%c",i,str1[i]);
! // //        
printf("device->words[%i][%i]=%c\n",device->wordCount,i,device->words[device->wordCount][i]);
! //         device->words[device->wordCount][i]=str1[i];
! //       }
! //       device->wordCount++;
! //     }
! //   }
! //   return;
! // 
! 
    if((hdr->type == PLAYER_MSGTYPE_DATA) && (hdr->subtype == 
PLAYER_SPEECH_RECOGNITION_DATA_STRING ))
    {
      player_speech_recognition_data_t *data = 
(player_speech_recognition_data_t*)buffer;
-     char * str1=NULL;
-     int i;
-     memset(device->rawText,0,PLAYER_SPEECH_RECOGNITION_TEXT_LEN*sizeof(char));
-     memset(device->words,0,30*20*sizeof(char));
-     device->wordCount = 0;
-    printf("data->text %s\n",data->text);
-     for (i=0;i<data->text_count;i++)
-       device->rawText[i]=data->text[i];
  
!     for (str1 = strtok(device->rawText, " ") ; str1 != NULL ; str1 = 
strtok(NULL, " ") )
!     {
!       for (i=0;i<strlen(str1);i++)
!       {
!         device->words[device->wordCount][i]=str1[i];
!        printf("str1[%d]=%c",i,str1[i]);
!        
printf("device->words[%i][%i]=%c\n",device->wordCount,i,device->words[device->wordCount][i]);
  
!       }
!       device->wordCount++;
      }
    }
--- 44,72 ----
  void playerc_speech_recognition_putmsg(playerc_speechrecognition_t *device, 
player_msghdr_t *hdr, player_speech_recognition_data_t *buffer, size_t len)
  {
!   int ii,jj;
!       
    if((hdr->type == PLAYER_MSGTYPE_DATA) && (hdr->subtype == 
PLAYER_SPEECH_RECOGNITION_DATA_STRING ))
    {
      player_speech_recognition_data_t *data = 
(player_speech_recognition_data_t*)buffer;
  
!     device->rawText = 
realloc(device->rawText,data->text_count*sizeof(device->rawText[0]));
!     memcpy(device->rawText, data->text, 
data->text_count*sizeof(device->rawText[0]));
!     device->rawText[data->text_count-1] = '\0';
  
!     device->wordCount = 1;
!     printf("data->text %s\n",data->text);
! 
!     for (ii = 0; ii < data->text_count; ++ii)
!     {
!       if (device->rawText[ii] == ' ')
!         device->wordCount++;
!     }
!     device->words = 
realloc(device->words,device->wordCount*sizeof(device->words[0]));
!     
!     jj = 0;
!     for (ii = 0; ii < data->text_count; ++ii)
!     {
!       if (device->rawText[ii] == ' ')
!         device->words[jj++] = &device->rawText[ii+1];
      }
    }

Index: dev_aio.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_aio.c,v
retrieving revision 1.2
retrieving revision 1.2.2.1
diff -C2 -d -r1.2 -r1.2.2.1
*** dev_aio.c   20 Apr 2006 12:17:31 -0000      1.2
--- dev_aio.c   10 Sep 2007 04:11:00 -0000      1.2.2.1
***************
*** 74,77 ****
--- 74,78 ----
  {
    playerc_device_term(&device->info);
+   free(device->voltages);
    free(device);
  }
***************
*** 97,102 ****
       (header->subtype == PLAYER_AIO_DATA_STATE))
    {
-     assert(data->voltages_count <= PLAYER_AIO_MAX_INPUTS);
      device->voltages_count = data->voltages_count;
      memcpy(device->voltages,
             data->voltages,
--- 98,103 ----
       (header->subtype == PLAYER_AIO_DATA_STATE))
    {
      device->voltages_count = data->voltages_count;
+     device->voltages = realloc(device->voltages, device->voltages_count * 
sizeof(device->voltages[0]));
      memcpy(device->voltages,
             data->voltages,

Index: dev_graphics3d.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_graphics3d.c,v
retrieving revision 1.2
retrieving revision 1.2.4.1
diff -C2 -d -r1.2 -r1.2.4.1
*** dev_graphics3d.c    12 May 2006 22:59:59 -0000      1.2
--- dev_graphics3d.c    10 Sep 2007 04:11:00 -0000      1.2.4.1
***************
*** 89,97 ****
    player_graphics3d_cmd_draw_t cmd;
  
-   /* limit the number of points we can draw */
    cmd.draw_mode = mode;
-   count = MIN(count,PLAYER_GRAPHICS3D_MAX_POINTS);
    cmd.points_count = count;
!   memcpy( &cmd.points, pts, sizeof(player_point_3d_t)*count);
    cmd.color = device->color;
  
--- 89,95 ----
    player_graphics3d_cmd_draw_t cmd;
  
    cmd.draw_mode = mode;
    cmd.points_count = count;
!   cmd.points = pts;
    cmd.color = device->color;
  

Index: dev_rfid.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_rfid.c,v
retrieving revision 1.4
retrieving revision 1.4.2.1
diff -C2 -d -r1.4 -r1.4.2.1
*** dev_rfid.c  20 Aug 2007 06:37:26 -0000      1.4
--- dev_rfid.c  10 Sep 2007 04:11:00 -0000      1.4.2.1
***************
*** 55,60 ****
  void playerc_rfid_destroy(playerc_rfid_t *device)
  {
!     playerc_device_term(&device->info);
!     free(device);
  }
  
--- 55,66 ----
  void playerc_rfid_destroy(playerc_rfid_t *device)
  {
!   int i;
!   playerc_device_term(&device->info);
!   if (device->tags) 
!   {
!     for (i = 0; i < device->tags_count; i++)
!       free(device->tags[i].guid);
!   }
!   free(device);
  }
  
***************
*** 78,98 ****
                          void *data)
  {
!     int i, j;
  
!     if((header->type == PLAYER_MSGTYPE_DATA) &&
!        (header->subtype == PLAYER_RFID_DATA_TAGS))
      {
!       player_rfid_data_t* rfid_data = (player_rfid_data_t*)data;
!       device->tags_count = rfid_data->tags_count;
!       for (i = 0; i < device->tags_count; i++)
!       {
!           if (i >= PLAYERC_RFID_MAX_TAGS)
!               break;
!           device->tags[i].type = rfid_data->tags[i].type;
!           for (j = 0; j < PLAYERC_RFID_MAX_GUID; j++)
!               device->tags[i].guid[j] = rfid_data->tags[i].guid[j];
!       }
      }
!     else
        PLAYERC_WARN2("skipping rfid message with unknown type/subtype: 
%s/%d\n",
            msgtype_to_str(header->type), header->subtype);
--- 84,111 ----
                          void *data)
  {
!   int i;
  
!   if((header->type == PLAYER_MSGTYPE_DATA) &&
!       (header->subtype == PLAYER_RFID_DATA_TAGS))
!   {
!     player_rfid_data_t* rfid_data = (player_rfid_data_t*)data;
!     // clean up our existing tags
!     if (device->tags) 
      {
!       for (i = 0; i < device->tags_count; i++)
!         free(device->tags[i].guid);
      }
!     device->tags_count = rfid_data->tags_count;
!     device->tags = realloc(device->tags,device->tags_count * 
sizeof(device->tags[0]));
!     memset(device->tags,0,device->tags_count * sizeof(device->tags[0]));
!     for (i = 0; i < device->tags_count; i++)
!     {
!       device->tags[i].type = rfid_data->tags[i].type;
!       device->tags[i].guid_count = rfid_data->tags[i].guid_count;
!       device->tags[i].guid = malloc(device->tags[i].guid_count);
!       
memcpy(device->tags[i].guid,rfid_data->tags[i].guid,device->tags[i].guid_count);
!     }
!   }
!   else
        PLAYERC_WARN2("skipping rfid message with unknown type/subtype: 
%s/%d\n",
            msgtype_to_str(header->type), header->subtype);

Index: dev_map.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_map.c,v
retrieving revision 1.9
retrieving revision 1.9.6.1
diff -C2 -d -r1.9 -r1.9.6.1
*** dev_map.c   13 Oct 2005 18:54:54 -0000      1.9
--- dev_map.c   10 Sep 2007 04:11:00 -0000      1.9.6.1
***************
*** 48,54 ****
  #endif
  
! #if HAVE_ZLIB_H
!   #include <zlib.h>
! #endif
  
  #include <assert.h>
--- 48,54 ----
  #endif
  
! //#if HAVE_ZLIB_H
! //  #include <zlib.h>
! //#endif
  
  #include <assert.h>
***************
*** 104,114 ****
    int i,j;
    int oi,oj;
!   int sx,sy;
    int si,sj;
    char* cell;
! #if HAVE_ZLIB_H
!   uLongf unzipped_data_len;
!   char* unzipped_data;
! #endif
  
  
--- 104,114 ----
    int i,j;
    int oi,oj;
! //  int sx,sy;
    int si,sj;
    char* cell;
! //#if HAVE_ZLIB_H
! //  uLongf unzipped_data_len;
! //  char* unzipped_data;
! //#endif
  
  
***************
*** 130,136 ****
  
    // Allocate space for the whole map
!   if(device->cells)
!     free(device->cells);
!   device->cells = (char*)malloc(sizeof(char) *
                                  device->width * device->height);
    assert(device->cells);
--- 130,134 ----
  
    // Allocate space for the whole map
!   device->cells = (char*)realloc(device->cells, sizeof(char) *
                                  device->width * device->height);
    assert(device->cells);
***************
*** 145,163 ****
    assert(data_req);
  
! #if HAVE_ZLIB_H
!   // Allocate a buffer into which we'll decompress the map data
!   unzipped_data_len = PLAYER_MAP_MAX_TILE_SIZE;
!   unzipped_data = (char*)malloc(unzipped_data_len);
!   assert(unzipped_data);
! #endif
  
    // Tile size
!   sy = sx = (int)sqrt(PLAYER_MAP_MAX_TILE_SIZE);
!   assert(sx * sy < (int)(PLAYER_MAP_MAX_TILE_SIZE));
    oi=oj=0;
    while((oi < device->width) && (oj < device->height))
    {
!     si = MIN(sx, device->width - oi);
!     sj = MIN(sy, device->height - oj);
  
      memset(data_req,0,repsize);
--- 143,161 ----
    assert(data_req);
  
! //#if HAVE_ZLIB_H
! //  // Allocate a buffer into which we'll decompress the map data
! //  unzipped_data_len = PLAYER_MAP_MAX_TILE_SIZE;
! //  unzipped_data = (char*)malloc(unzipped_data_len);
! //  assert(unzipped_data);
! //#endif
  
    // Tile size
! //  sy = sx = (int)sqrt(PLAYER_MAP_MAX_TILE_SIZE);
! //  assert(sx * sy < (int)(PLAYER_MAP_MAX_TILE_SIZE));
    oi=oj=0;
    while((oi < device->width) && (oj < device->height))
    {
!     si = device->width - oi;
!     sj = device->height - oj;
  
      memset(data_req,0,repsize);
***************
*** 174,195 ****
        free(data_req);
        free(device->cells);
! #if HAVE_ZLIB_H
!       free(unzipped_data);
! #endif
        return(-1);
      }
  
! #if HAVE_ZLIB_H
!     unzipped_data_len = PLAYER_MAP_MAX_TILE_SIZE;
!     if(uncompress((Bytef*)unzipped_data, &unzipped_data_len,
!                   data_req->data, data_req->data_count) != Z_OK)
!     {
!       PLAYERC_ERR("failed to decompress map data");
!       free(data_req);
!       free(device->cells);
!       free(unzipped_data);
!       return(-1);
!     }
! #endif
  
      // copy the map data
--- 172,193 ----
        free(data_req);
        free(device->cells);
! //#if HAVE_ZLIB_H
! //      free(unzipped_data);
! //#endif
        return(-1);
      }
  
! //#if HAVE_ZLIB_H
! //    unzipped_data_len = PLAYER_MAP_MAX_TILE_SIZE;
! //    if(uncompress((Bytef*)unzipped_data, &unzipped_data_len,
! //                  data_req->data, data_req->data_count) != Z_OK)
! //    {
! //      PLAYERC_ERR("failed to decompress map data");
! //      free(data_req);
! //      free(device->cells);
! //      free(unzipped_data);
! //      return(-1);
! //    }
! //#endif
  
      // copy the map data
***************
*** 199,207 ****
        {
          cell = device->cells + PLAYERC_MAP_INDEX(device,oi+i,oj+j);
! #if HAVE_ZLIB_H
!         *cell = unzipped_data[j*si + i];
! #else
          *cell = data_req->data[j*si + i];
! #endif
        }
      }
--- 197,205 ----
        {
          cell = device->cells + PLAYERC_MAP_INDEX(device,oi+i,oj+j);
! //#if HAVE_ZLIB_H
! //        *cell = unzipped_data[j*si + i];
! //#else
          *cell = data_req->data[j*si + i];
! //#endif
        }
      }
***************
*** 215,221 ****
    }
  
! #if HAVE_ZLIB_H
!   free(unzipped_data);
! #endif
    free(data_req);
  
--- 213,219 ----
    }
  
! //#if HAVE_ZLIB_H
! //  free(unzipped_data);
! //#endif
    free(data_req);
  

Index: dev_pointcloud3d.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_pointcloud3d.c,v
retrieving revision 1.2
retrieving revision 1.2.2.1
diff -C2 -d -r1.2 -r1.2.2.1
*** dev_pointcloud3d.c  14 Mar 2007 16:41:51 -0000      1.2
--- dev_pointcloud3d.c  10 Sep 2007 04:11:00 -0000      1.2.2.1
***************
*** 55,58 ****
--- 55,59 ----
  {
    playerc_device_term (&device->info);
+   free (device->points);
    free (device);
  
***************
*** 82,86 ****
      {
        player_pointcloud3d_data_t* pc3_data = 
(player_pointcloud3d_data_t*)data;
!         device->points_count = MIN (pc3_data->points_count, 
PLAYERC_POINTCLOUD3D_MAX_POINTS);
          memcpy (device->points, pc3_data->points,
                sizeof (player_pointcloud3d_element_t)*device->points_count);
--- 83,88 ----
      {
        player_pointcloud3d_data_t* pc3_data = 
(player_pointcloud3d_data_t*)data;
!         device->points_count = pc3_data->points_count;
!         device->points = realloc(device->points, 
device->points_count*sizeof(device->points[0]));
          memcpy (device->points, pc3_data->points,
                sizeof (player_pointcloud3d_element_t)*device->points_count);

Index: dev_actarray.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_actarray.c,v
retrieving revision 1.11
retrieving revision 1.11.2.1
diff -C2 -d -r1.11 -r1.11.2.1
*** dev_actarray.c      20 Aug 2007 06:37:26 -0000      1.11
--- dev_actarray.c      10 Sep 2007 04:11:00 -0000      1.11.2.1
***************
*** 66,69 ****
--- 66,71 ----
  {
    playerc_device_term(&device->info);
+   free(device->actuators_data);
+   free(device->actuators_geom);
    free(device);
  }
***************
*** 90,100 ****
    {
      device->actuators_count = data->actuators_count;
      for (i = 0; i < device->actuators_count; i++)
      {
!       device->actuators_data[i].position = data->actuators[i].position;
!       device->actuators_data[i].speed = data->actuators[i].speed;
!       device->actuators_data[i].acceleration = 
data->actuators[i].acceleration;
!       device->actuators_data[i].state = data->actuators[i].state;
!       device->actuators_data[i].current = data->actuators[i].current;
      }
      device->motor_state = data->motor_state;
--- 92,99 ----
    {
      device->actuators_count = data->actuators_count;
+     device->actuators_data = 
realloc(device->actuators_data,device->actuators_count*sizeof(device->actuators_data[0]));
      for (i = 0; i < device->actuators_count; i++)
      {
!       device->actuators_data[i] = data->actuators[i];
      }
      device->motor_state = data->motor_state;
***************
*** 115,134 ****
      return result;
  
    for (ii = 0; ii < device->actuators_count; ii++)
    {
!     device->actuators_geom[ii].type = geom.actuators[ii].type;
!     device->actuators_geom[ii].length = geom.actuators[ii].length;
!     device->actuators_geom[ii].orientation.proll = 
geom.actuators[ii].orientation.proll;
!     device->actuators_geom[ii].orientation.ppitch = 
geom.actuators[ii].orientation.ppitch;
!     device->actuators_geom[ii].orientation.pyaw = 
geom.actuators[ii].orientation.pyaw;
!     device->actuators_geom[ii].axis.px = geom.actuators[ii].axis.px;
!     device->actuators_geom[ii].axis.py = geom.actuators[ii].axis.py;
!     device->actuators_geom[ii].axis.pz = geom.actuators[ii].axis.pz;
!     device->actuators_geom[ii].min = geom.actuators[ii].min;
!     device->actuators_geom[ii].centre = geom.actuators[ii].centre;
!     device->actuators_geom[ii].max = geom.actuators[ii].max;
!     device->actuators_geom[ii].home = geom.actuators[ii].home;
!     device->actuators_geom[ii].config_speed = geom.actuators[ii].config_speed;
!     device->actuators_geom[ii].hasbrakes = geom.actuators[ii].hasbrakes;
    }
    device->base_pos = geom.base_pos;
--- 114,121 ----
      return result;
  
+   device->actuators_geom = 
realloc(device->actuators_geom,device->actuators_count*sizeof(device->actuators_geom[0]));
    for (ii = 0; ii < device->actuators_count; ii++)
    {
!     device->actuators_geom[ii] = geom.actuators[ii];
    }
    device->base_pos = geom.base_pos;
***************
*** 152,162 ****
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float 
positions[PLAYER_ACTARRAY_NUM_ACTUATORS])
  {
    player_actarray_multi_position_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   memcpy(&cmd.positions,positions, sizeof(float) * 
PLAYER_ACTARRAY_NUM_ACTUATORS);
!   cmd.positions_count = device->actuators_count;
  
    return playerc_client_write(device->info.client, &device->info,
--- 139,149 ----
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float 
*positions, int positions_count)
  {
    player_actarray_multi_position_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   cmd.positions=positions;
!   cmd.positions_count = positions_count;
  
    return playerc_client_write(device->info.client, &device->info,
***************
*** 182,192 ****
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float 
speeds[PLAYER_ACTARRAY_NUM_ACTUATORS])
  {
    player_actarray_multi_speed_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   memcpy(&cmd.speeds,speeds,sizeof(float) * PLAYER_ACTARRAY_NUM_ACTUATORS);
!   cmd.speeds_count = device->actuators_count;
  
    return playerc_client_write(device->info.client, &device->info,
--- 169,179 ----
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float 
*speeds, int speeds_count)
  {
    player_actarray_multi_speed_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   cmd.speeds = speeds;
!   cmd.speeds_count = speeds_count;
  
    return playerc_client_write(device->info.client, &device->info,
***************
*** 224,234 ****
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float 
currents[PLAYER_ACTARRAY_NUM_ACTUATORS])
  {
    player_actarray_multi_current_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   memcpy(&cmd.currents,currents,sizeof(float) * 
PLAYER_ACTARRAY_NUM_ACTUATORS);
!   cmd.currents_count = device->actuators_count;
  
    return playerc_client_write(device->info.client, &device->info,
--- 211,221 ----
  
  // Command all joints in the array to move with a specified current
! int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float 
*currents, int currents_count)
  {
    player_actarray_multi_current_cmd_t cmd;
  
    memset(&cmd, 0, sizeof(cmd));
!   cmd.currents = currents;
!   cmd.currents_count = currents_count;
  
    return playerc_client_write(device->info.client, &device->info,

Index: dev_graphics2d.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_graphics2d.c,v
retrieving revision 1.8
retrieving revision 1.8.2.1
diff -C2 -d -r1.8 -r1.8.2.1
*** dev_graphics2d.c    12 May 2006 22:59:59 -0000      1.8
--- dev_graphics2d.c    10 Sep 2007 04:11:00 -0000      1.8.2.1
***************
*** 87,94 ****
    player_graphics2d_cmd_points_t cmd;
  
-   /* limit the number of points we can draw */
-   count = MIN(count,PLAYER_GRAPHICS2D_MAX_POINTS);
    cmd.points_count = count;
!   memcpy( &cmd.points, pts, sizeof(player_point_2d_t)*count);
    cmd.color = device->color;
  
--- 87,92 ----
    player_graphics2d_cmd_points_t cmd;
  
    cmd.points_count = count;
!   cmd.points= pts;
    cmd.color = device->color;
  
***************
*** 105,113 ****
    player_graphics2d_cmd_polyline_t cmd;
    
-   /* limit the number of points we can draw */
-   count = MIN(count,PLAYER_GRAPHICS2D_MAX_POINTS);
    cmd.points_count = count;
!   memcpy( &cmd.points, pts, sizeof(player_point_2d_t)*count);
!  cmd.color = device->color;
     
    return playerc_client_write(device->info.client, &device->info,
--- 103,109 ----
    player_graphics2d_cmd_polyline_t cmd;
    
    cmd.points_count = count;
!   cmd.points = pts;
!   cmd.color = device->color;
     
    return playerc_client_write(device->info.client, &device->info,
***************
*** 124,131 ****
    player_graphics2d_cmd_polygon_t cmd;
  
-   /* limit the number of points we can draw */
-   count = MIN(count,PLAYER_GRAPHICS2D_MAX_POINTS);
    cmd.points_count = count;
!   memcpy( &cmd.points, pts, sizeof(player_point_2d_t)*count);
    cmd.color = device->color;
    cmd.filled = filled;
--- 120,125 ----
    player_graphics2d_cmd_polygon_t cmd;
  
    cmd.points_count = count;
!   cmd.points = pts;
    cmd.color = device->color;
    cmd.filled = filled;

Index: playerc.h
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/playerc.h,v
retrieving revision 1.229
retrieving revision 1.229.2.1
diff -C2 -d -r1.229 -r1.229.2.1
*** playerc.h   21 Aug 2007 23:16:23 -0000      1.229
--- playerc.h   10 Sep 2007 04:11:00 -0000      1.229.2.1
***************
*** 100,119 ****
  
  
- /***************************************************************************
-  * Array sizes
-  **************************************************************************/
- 
- #define PLAYERC_MAX_DEVICES             PLAYER_MAX_DEVICES
- #define PLAYERC_LASER_MAX_SAMPLES       PLAYER_LASER_MAX_SAMPLES
- #define PLAYERC_FIDUCIAL_MAX_SAMPLES    PLAYER_FIDUCIAL_MAX_SAMPLES
- #define PLAYERC_SONAR_MAX_SAMPLES       PLAYER_SONAR_MAX_SAMPLES
- #define PLAYERC_BUMPER_MAX_SAMPLES      PLAYER_BUMPER_MAX_SAMPLES
- #define PLAYERC_IR_MAX_SAMPLES          PLAYER_IR_MAX_SAMPLES
- #define PLAYERC_BLOBFINDER_MAX_BLOBS    PLAYER_BLOBFINDER_MAX_BLOBS
- #define PLAYERC_WIFI_MAX_LINKS          PLAYER_WIFI_MAX_LINKS
- #define PLAYERC_RFID_MAX_TAGS           PLAYER_RFID_MAX_TAGS
- #define PLAYERC_RFID_MAX_GUID           PLAYER_RFID_MAX_GUID
- #define PLAYERC_POINTCLOUD3D_MAX_POINTS PLAYER_POINTCLOUD3D_MAX_POINTS
- 
  /** @} */
  
--- 100,103 ----
***************
*** 484,488 ****
    /** List of available (but not necessarily subscribed) devices.
        This list is filled in by playerc_client_get_devlist(). */
!   playerc_device_info_t devinfos[PLAYERC_MAX_DEVICES];
    int devinfo_count;
  
--- 468,472 ----
    /** List of available (but not necessarily subscribed) devices.
        This list is filled in by playerc_client_get_devlist(). */
!   playerc_device_info_t devinfos[PLAYER_MAX_DEVICES];
    int devinfo_count;
  
***************
*** 881,885 ****
  
    /// A bitfield of the current digital inputs.
!   float voltages[PLAYER_AIO_MAX_INPUTS];
  
  } playerc_aio_t;
--- 865,869 ----
  
    /// A bitfield of the current digital inputs.
!   float *voltages;
  
  } playerc_aio_t;
***************
*** 934,939 ****
    uint32_t actuators_count;
    /** The actuator data, geometry and motor state. */
!   player_actarray_actuator_t actuators_data[PLAYER_ACTARRAY_NUM_ACTUATORS];
!   player_actarray_actuatorgeom_t 
actuators_geom[PLAYER_ACTARRAY_NUM_ACTUATORS];
    /** Reports if the actuators are off (0) or on (1) */
    uint8_t motor_state;
--- 918,923 ----
    uint32_t actuators_count;
    /** The actuator data, geometry and motor state. */
!   player_actarray_actuator_t *actuators_data;
!   player_actarray_actuatorgeom_t *actuators_geom;
    /** Reports if the actuators are off (0) or on (1) */
    uint8_t motor_state;
***************
*** 964,968 ****
  
  /** @brief Command all joints in the array to move to specified positions. */
! int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float 
positions[PLAYER_ACTARRAY_NUM_ACTUATORS]);
  
  /** @brief Command a joint in the array to move at a specified speed. */
--- 948,952 ----
  
  /** @brief Command all joints in the array to move to specified positions. */
! int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float 
*positions, int positions_count);
  
  /** @brief Command a joint in the array to move at a specified speed. */
***************
*** 970,974 ****
  
  /** @brief Command a joint in the array to move at a specified speed. */
! int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float 
speeds[PLAYER_ACTARRAY_NUM_ACTUATORS]);
  
  /** @brief Command a joint (or, if joint is -1, the whole array) to go to its 
home position. */
--- 954,958 ----
  
  /** @brief Command a joint in the array to move at a specified speed. */
! int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float 
*speeds, int speeds_count);
  
  /** @brief Command a joint (or, if joint is -1, the whole array) to go to its 
home position. */
***************
*** 979,983 ****
  
  /** @brief Command all joints in the array to move with specified currents. */
! int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float 
currents[PLAYER_ACTARRAY_NUM_ACTUATORS]);
  
  
--- 963,967 ----
  
  /** @brief Command all joints in the array to move with specified currents. */
! int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float 
*currents, int currents_count);
  
  
***************
*** 1117,1121 ****
    /** A list of detected blobs. */
    unsigned int blobs_count;
!   playerc_blobfinder_blob_t blobs[PLAYER_BLOBFINDER_MAX_BLOBS];
  
  } playerc_blobfinder_t;
--- 1101,1105 ----
    /** A list of detected blobs. */
    unsigned int blobs_count;
!   playerc_blobfinder_blob_t *blobs;
  
  } playerc_blobfinder_t;
***************
*** 1161,1165 ****
        This structure is filled by calling playerc_bumper_get_geom().
        values are x,y (of center) ,normal,length,curvature */
!   player_bumper_define_t poses[PLAYERC_BUMPER_MAX_SAMPLES];
  
    /** Number of points in the scan. */
--- 1145,1149 ----
        This structure is filled by calling playerc_bumper_get_geom().
        values are x,y (of center) ,normal,length,curvature */
!   player_bumper_define_t *poses;
  
    /** Number of points in the scan. */
***************
*** 1167,1171 ****
  
    /** Bump data: unsigned char, either boolean or code indicating corner. */
!   uint8_t bumpers[PLAYERC_BUMPER_MAX_SAMPLES];
  
  } playerc_bumper_t;
--- 1151,1155 ----
  
    /** Bump data: unsigned char, either boolean or code indicating corner. */
!   uint8_t *bumpers;
  
  } playerc_bumper_t;
***************
*** 1236,1240 ****
        correct host byte ordering.
    */
!   uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
  
  } playerc_camera_t;
--- 1220,1224 ----
        correct host byte ordering.
    */
!   uint8_t *image;
  
  } playerc_camera_t;
***************
*** 1335,1339 ****
    /** List of detected beacons. */
    int fiducials_count;
!   player_fiducial_item_t fiducials[PLAYERC_FIDUCIAL_MAX_SAMPLES];
  
  } playerc_fiducial_t;
--- 1319,1323 ----
    /** List of detected beacons. */
    int fiducials_count;
!   player_fiducial_item_t *fiducials;
  
  } playerc_fiducial_t;
***************
*** 1760,1775 ****
  
    /** Raw range data; range (m). */
!   double ranges[PLAYERC_LASER_MAX_SAMPLES];
  
    /** Scan data; range (m) and bearing (radians). */
!   double scan[PLAYERC_LASER_MAX_SAMPLES][2];
  
    /** Scan data; x, y position (m). */
!   player_point_2d_t point[PLAYERC_LASER_MAX_SAMPLES];
  
    /** Scan reflection intensity values (0-3).  Note that the intensity
        values will only be filled if intensity information is enabled
        (using the set_config function). */
!   int intensity[PLAYERC_LASER_MAX_SAMPLES];
  
    /** ID for this scan */
--- 1744,1759 ----
  
    /** Raw range data; range (m). */
!   double *ranges;
  
    /** Scan data; range (m) and bearing (radians). */
!   double *scan[2];
  
    /** Scan data; x, y position (m). */
!   player_point_2d_t *point;
  
    /** Scan reflection intensity values (0-3).  Note that the intensity
        values will only be filled if intensity information is enabled
        (using the set_config function). */
!   int *intensity;
  
    /** ID for this scan */
***************
*** 1994,2003 ****
    /** List of possible poses. */
    int hypoth_count;
!   player_localize_hypoth_t hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
  
    double mean[3];
    double variance;
    int num_particles;
!   playerc_localize_particle_t particles[PLAYER_LOCALIZE_PARTICLES_MAX];
  
  } playerc_localize_t;
--- 1978,1987 ----
    /** List of possible poses. */
    int hypoth_count;
!   player_localize_hypoth_t *hypoths;
  
    double mean[3];
    double variance;
    int num_particles;
!   playerc_localize_particle_t *particles;
  
  } playerc_localize_t;
***************
*** 2217,2221 ****
  
    /** Data  */
!   uint8_t data[PLAYER_OPAQUE_MAX_SIZE];
  } playerc_opaque_t;
  
--- 2201,2205 ----
  
    /** Data  */
!   uint8_t *data;
  } playerc_opaque_t;
  
***************
*** 2282,2286 ****
    /** List of waypoints in the current plan (m,m,radians).  Call
        playerc_planner_get_waypoints() to fill this in. */
!   double waypoints[PLAYER_PLANNER_MAX_WAYPOINTS][3];
  
  } playerc_planner_t;
--- 2266,2270 ----
    /** List of waypoints in the current plan (m,m,radians).  Call
        playerc_planner_get_waypoints() to fill this in. */
!   double *waypoints[3];
  
  } playerc_planner_t;
***************
*** 2878,2882 ****
    /** Pose of each sonar relative to robot (m, m, radians).  This
        structure is filled by calling playerc_sonar_get_geom(). */
!   player_pose3d_t poses[PLAYERC_SONAR_MAX_SAMPLES];
  
    /** Number of points in the scan. */
--- 2862,2866 ----
    /** Pose of each sonar relative to robot (m, m, radians).  This
        structure is filled by calling playerc_sonar_get_geom(). */
!   player_pose3d_t *poses;
  
    /** Number of points in the scan. */
***************
*** 2884,2888 ****
  
    /** Scan data: range (m). */
!   double scan[PLAYERC_SONAR_MAX_SAMPLES];
  
  } playerc_sonar_t;
--- 2868,2872 ----
  
    /** Scan data: range (m). */
!   double *scan;
  
  } playerc_sonar_t;
***************
*** 2956,2960 ****
  
    /** A list containing info for each link. */
!   playerc_wifi_link_t links[PLAYERC_WIFI_MAX_LINKS];
    int link_count;
  
--- 2940,2944 ----
  
    /** A list containing info for each link. */
!   playerc_wifi_link_t *links;
    int link_count;
  
***************
*** 3099,3106 ****
    playerc_device_t info;
  
!   char rawText[PLAYER_SPEECH_RECOGNITION_TEXT_LEN];
    // Just estimating that no more than 20 words will be spoken between 
updates.
    // Assuming that the longest word is <= 30 characters.
!   char words[20][30];
    int wordCount;
  } playerc_speechrecognition_t;
--- 3083,3090 ----
    playerc_device_t info;
  
!   char *rawText;
    // Just estimating that no more than 20 words will be spoken between 
updates.
    // Assuming that the longest word is <= 30 characters.
!   char **words;
    int wordCount;
  } playerc_speechrecognition_t;
***************
*** 3139,3143 ****
      uint32_t guid_count;
      /** The Globally Unique IDentifier (GUID) of the tag. */
!     uint8_t guid[PLAYERC_RFID_MAX_GUID];
  }  playerc_rfidtag_t;
  
--- 3123,3127 ----
      uint32_t guid_count;
      /** The Globally Unique IDentifier (GUID) of the tag. */
!     uint8_t *guid;
  }  playerc_rfidtag_t;
  
***************
*** 3152,3156 ****
  
    /** The list of RFID tags. */
!   playerc_rfidtag_t tags[PLAYERC_RFID_MAX_TAGS];
  } playerc_rfid_t;
  
--- 3136,3140 ----
  
    /** The list of RFID tags. */
!   playerc_rfidtag_t *tags;
  } playerc_rfid_t;
  
***************
*** 3193,3197 ****
  
    /** The list of 3D pointcloud elements. */
!   playerc_pointcloud3d_element_t points[PLAYERC_POINTCLOUD3D_MAX_POINTS];
  } playerc_pointcloud3d_t;
  
--- 3177,3181 ----
  
    /** The list of 3D pointcloud elements. */
!   playerc_pointcloud3d_element_t *points;
  } playerc_pointcloud3d_t;
  

Index: dev_simulation.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_simulation.c,v
retrieving revision 1.14
retrieving revision 1.14.2.1
diff -C2 -d -r1.14 -r1.14.2.1
*** dev_simulation.c    20 Apr 2007 00:59:47 -0000      1.14
--- dev_simulation.c    10 Sep 2007 04:11:00 -0000      1.14.2.1
***************
*** 109,114 ****
  
    memset(&cmd, 0, sizeof(cmd));
!   strncpy(cmd.name, name, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   cmd.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    cmd.name_count = strlen(cmd.name) + 1;
    cmd.pose.px = gx;
--- 109,113 ----
  
    memset(&cmd, 0, sizeof(cmd));
!   cmd.name = name;
    cmd.name_count = strlen(cmd.name) + 1;
    cmd.pose.px = gx;
***************
*** 128,133 ****
    
    memset(&cfg, 0, sizeof(cfg));
!   strncpy(cfg.name, identifier, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   cfg.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
--- 127,131 ----
    
    memset(&cfg, 0, sizeof(cfg));
!   cfg.name = identifier;
    cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
***************
*** 148,153 ****
  
    memset(&cmd, 0, sizeof(cmd));
!   strncpy(cmd.name, name, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   cmd.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    cmd.name_count = strlen(cmd.name) + 1;
    cmd.pose.px = gx;
--- 146,150 ----
  
    memset(&cmd, 0, sizeof(cmd));
!   cmd.name = name;
    cmd.name_count = strlen(cmd.name) + 1;
    cmd.pose.px = gx;
***************
*** 170,175 ****
    
    memset(&cfg, 0, sizeof(cfg));
!   strncpy(cfg.name, identifier, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   cfg.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
--- 167,171 ----
    
    memset(&cfg, 0, sizeof(cfg));
!   cfg.name = identifier;
    cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
***************
*** 197,216 ****
  
    memset(&req, 0, sizeof(req));
!   strncpy(req.name, name, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   req.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    req.name_count = strlen(req.name) + 1;
    
!   strncpy(req.prop, property, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   req.prop[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    req.prop_count = strlen(req.prop) + 1;
  
!   if( value_len > PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN )
!     {
!       PLAYER_WARN2( "Simulation property data exceeds maximum length (%d/%d 
bytes).",
!                  value_len,  PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN );
!       value_len = PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN;
!     }
!   
!   memcpy( req.value, value, value_len );
    req.value_count = value_len;
    
--- 193,203 ----
  
    memset(&req, 0, sizeof(req));
!   req.name = name;
    req.name_count = strlen(req.name) + 1;
    
!   req.prop = property;
    req.prop_count = strlen(req.prop) + 1;
  
!   req.value = value;
    req.value_count = value_len;
    
***************
*** 230,249 ****
  
    memset(&req, 0, sizeof(req));
!   strncpy(req.name, name, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   req.name[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    req.name_count = strlen(req.name) + 1;
    
!   strncpy(req.prop, property, PLAYER_SIMULATION_IDENTIFIER_MAXLEN);
!   req.prop[PLAYER_SIMULATION_IDENTIFIER_MAXLEN-1]='\0';
    req.prop_count = strlen(req.prop) + 1;
  
!   if( value_len > PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN )
!     {
!       PLAYER_WARN2( "Simulation property data exceeds maximum length (%d/%d 
bytes).",
!                  value_len,  PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN );
!       value_len = PLAYER_SIMULATION_PROPERTY_DATA_MAXLEN;
!     }
!   
!   req.value_count = value_len;
    
    if( playerc_client_request(device->info.client, &device->info, 
--- 217,228 ----
  
    memset(&req, 0, sizeof(req));
!   req.name = name;
    req.name_count = strlen(req.name) + 1;
    
!   req.prop = property;
    req.prop_count = strlen(req.prop) + 1;
  
!   req.value = NULL;
!   req.value_count = 0;
    
    if( playerc_client_request(device->info.client, &device->info, 

Index: dev_speech.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_speech.c,v
retrieving revision 1.5
retrieving revision 1.5.4.1
diff -C2 -d -r1.5 -r1.5.4.1
*** dev_speech.c        12 Feb 2006 00:54:38 -0000      1.5
--- dev_speech.c        10 Sep 2007 04:11:00 -0000      1.5.4.1
***************
*** 96,105 ****
    
    memset(&cmd, 0, sizeof(cmd));
!       
!   if (str)
!   {
!     strncpy ((char *) (cmd.string), str, PLAYER_SPEECH_MAX_STRING_LEN);
!     cmd.string_count = strlen(str) + 1; 
!   }
        
    return playerc_client_write(device->info.client, 
--- 96,101 ----
    
    memset(&cmd, 0, sizeof(cmd));
!   cmd.string = str;
!   cmd.string_count = strlen(str) + 1; 
        
    return playerc_client_write(device->info.client, 


-------------------------------------------------------------------------
This SF.net email is sponsored by: Microsoft
Defy all challenges. Microsoft(R) Visual Studio 2005.
http://clk.atdmt.com/MRT/go/vse0120000070mrt/direct/01/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to