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

Modified Files:
      Tag: b_thjc_dynamic_arrays
        dev_map.c playerc.h dev_speech.c dev_actarray.c 
        dev_simulation.c 
Log Message:
dynamic array changes to drivers compile, still needs testing
added lots more .cvsignore settings for eclipse

Index: dev_simulation.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_simulation.c,v
retrieving revision 1.14.2.2
retrieving revision 1.14.2.3
diff -C2 -d -r1.14.2.2 -r1.14.2.3
*** dev_simulation.c    10 Oct 2007 09:26:00 -0000      1.14.2.2
--- dev_simulation.c    19 Oct 2007 21:58:55 -0000      1.14.2.3
***************
*** 117,121 ****
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_POSE2D,
!                                 &cmd, NULL, 0);
  }
  
--- 117,121 ----
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_POSE2D,
!                                 &cmd, NULL);
  }
  
***************
*** 124,139 ****
                                  double *x, double *y, double *a)
  {
!   player_simulation_pose2d_req_t cfg;
    
    memset(&cfg, 0, sizeof(cfg));
!   cfg.name = identifier;
!   cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
                               PLAYER_SIMULATION_REQ_GET_POSE2D,
!                            &cfg, &cfg, sizeof(cfg)) < 0)
      return (-1);
!   *x =  cfg.pose.px;
!   *y =  cfg.pose.py;
!   *a =  cfg.pose.pa;
    return 0;
  }
--- 124,140 ----
                                  double *x, double *y, double *a)
  {
!   player_simulation_pose2d_req_t req, *cfg;
    
    memset(&cfg, 0, sizeof(cfg));
!   req.name = identifier;
!   req.name_count = strlen(req.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
                               PLAYER_SIMULATION_REQ_GET_POSE2D,
!                            &req, (void*)&cfg) < 0)
      return (-1);
!   *x =  cfg->pose.px;
!   *y =  cfg->pose.py;
!   *a =  cfg->pose.pa;
!   player_simulation_pose2d_req_t_free(cfg);
    return 0;
  }
***************
*** 157,161 ****
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_POSE3D,
!                                 &cmd, NULL, 0);
  }
  
--- 158,162 ----
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_POSE3D,
!                                 &cmd, NULL);
  }
  
***************
*** 164,183 ****
            double *x, double *y, double *z, double *roll, double *pitch, 
double *yaw, double *time)
  {
!   player_simulation_pose3d_req_t cfg;
    
!   memset(&cfg, 0, sizeof(cfg));
!   cfg.name = identifier;
!   cfg.name_count = strlen(cfg.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
                               PLAYER_SIMULATION_REQ_GET_POSE3D,
!            &cfg, &cfg, sizeof(cfg)) < 0)
      return (-1);
!   *x =  cfg.pose.px;
!   *y =  cfg.pose.py;
!   *z =  cfg.pose.pz;
!   *pitch =  cfg.pose.ppitch;
!   *roll =  cfg.pose.proll;
!   *yaw =  cfg.pose.pyaw;
!   *time = cfg.simtime;
    return 0;
  }
--- 165,185 ----
            double *x, double *y, double *z, double *roll, double *pitch, 
double *yaw, double *time)
  {
!   player_simulation_pose3d_req_t req, *cfg;
    
!   memset(&req, 0, sizeof(req));
!   req.name = identifier;
!   req.name_count = strlen(req.name) + 1;
    if (playerc_client_request(device->info.client, &device->info, 
                               PLAYER_SIMULATION_REQ_GET_POSE3D,
!            &req, (void*)&cfg) < 0)
      return (-1);
!   *x =  cfg->pose.px;
!   *y =  cfg->pose.py;
!   *z =  cfg->pose.pz;
!   *pitch =  cfg->pose.ppitch;
!   *roll =  cfg->pose.proll;
!   *yaw =  cfg->pose.pyaw;
!   *time = cfg->simtime;
!   player_simulation_pose3d_req_t_free(cfg);
    return 0;
  }
***************
*** 204,208 ****
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_PROPERTY,
!                                 &req, NULL, 0);
  }
  
--- 206,210 ----
    return playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_SET_PROPERTY,
!                                 &req, NULL);
  }
  
***************
*** 214,218 ****
                                    size_t value_len )
  {
!   player_simulation_property_req_t req;
  
    memset(&req, 0, sizeof(req));
--- 216,220 ----
                                    size_t value_len )
  {
!   player_simulation_property_req_t req,*resp;
  
    memset(&req, 0, sizeof(req));
***************
*** 228,235 ****
    if( playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_GET_PROPERTY,
!                                 &req, &req, sizeof(req)) < 0)
      return -1;
  
!   memcpy(value, req.value, value_len);
  
    return 0;
--- 230,238 ----
    if( playerc_client_request(device->info.client, &device->info, 
                                  PLAYER_SIMULATION_REQ_GET_PROPERTY,
!                                 &req, (void*)&resp) < 0)
      return -1;
  
!   memcpy(value, resp->value, value_len);
!   player_simulation_property_req_t_free(resp);
  
    return 0;

Index: dev_actarray.c
===================================================================
RCS file: 
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_actarray.c,v
retrieving revision 1.11.2.1
retrieving revision 1.11.2.2
diff -C2 -d -r1.11.2.1 -r1.11.2.2
*** dev_actarray.c      10 Sep 2007 04:11:00 -0000      1.11.2.1
--- dev_actarray.c      19 Oct 2007 21:58:55 -0000      1.11.2.2
***************
*** 107,115 ****
  int playerc_actarray_get_geom(playerc_actarray_t *device)
  {
!   player_actarray_geom_t geom;
    int ii = 0, result = 0;
  
    if((result = playerc_client_request(device->info.client, &device->info,
!       PLAYER_ACTARRAY_REQ_GET_GEOM, NULL, (void*)&geom, sizeof(geom))) < 0)
      return result;
  
--- 107,115 ----
  int playerc_actarray_get_geom(playerc_actarray_t *device)
  {
!   player_actarray_geom_t *geom;
    int ii = 0, result = 0;
  
    if((result = playerc_client_request(device->info.client, &device->info,
!       PLAYER_ACTARRAY_REQ_GET_GEOM, NULL, (void*)&geom)) < 0)
      return result;
  
***************
*** 117,124 ****
    for (ii = 0; ii < device->actuators_count; ii++)
    {
!     device->actuators_geom[ii] = geom.actuators[ii];
    }
!   device->base_pos = geom.base_pos;
!   device->base_orientation = geom.base_orientation;
    return 0;
  }
--- 117,125 ----
    for (ii = 0; ii < device->actuators_count; ii++)
    {
!     device->actuators_geom[ii] = geom->actuators[ii];
    }
!   device->base_pos = geom->base_pos;
!   device->base_orientation = geom->base_orientation;
!   player_actarray_geom_t_free(geom);
    return 0;
  }
***************
*** 233,237 ****
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_POWER,
!                                 &config, NULL, 0);
  }
  
--- 234,238 ----
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_POWER,
!                                 &config, NULL);
  }
  
***************
*** 245,249 ****
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_BRAKES,
!                                 &config, NULL, 0);
  }
  
--- 246,250 ----
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_BRAKES,
!                                 &config, NULL);
  }
  
***************
*** 258,262 ****
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_SPEED,
!                                 &config, NULL, 0);
  }
  
--- 259,263 ----
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_SPEED,
!                                 &config, NULL);
  }
  
***************
*** 271,275 ****
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_ACCEL,
!                                 &config, NULL, 0);
  }
  
--- 272,276 ----
    return playerc_client_request(device->info.client, &device->info,
                                  PLAYER_ACTARRAY_REQ_ACCEL,
!                                 &config, NULL);
  }
  

Index: dev_map.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_map.c,v
retrieving revision 1.9.6.2
retrieving revision 1.9.6.3
diff -C2 -d -r1.9.6.2 -r1.9.6.3
*** dev_map.c   10 Oct 2007 09:26:00 -0000      1.9.6.2
--- dev_map.c   19 Oct 2007 21:58:55 -0000      1.9.6.3
***************
*** 140,144 ****
  #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);
--- 140,144 ----
  #if HAVE_ZLIB_H
    // Allocate a buffer into which we'll decompress the map data
!   unzipped_data_len = device->width*device->height;
    unzipped_data = (char*)malloc(unzipped_data_len);
    assert(unzipped_data);
***************
*** 146,151 ****
  
    // 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))
--- 146,150 ----
  
    // Tile size
!   sy = sx = 640;
    oi=oj=0;
    while((oi < device->width) && (oj < device->height))
***************
*** 173,177 ****
  
  #if HAVE_ZLIB_H
!     unzipped_data_len = PLAYER_MAP_MAX_TILE_SIZE;
      if(uncompress((Bytef*)unzipped_data, &unzipped_data_len,
                    (uint8_t*)data_resp->data, data_resp->data_count) != Z_OK)
--- 172,176 ----
  
  #if HAVE_ZLIB_H
!     unzipped_data_len = device->width*device->height;
      if(uncompress((Bytef*)unzipped_data, &unzipped_data_len,
                    (uint8_t*)data_resp->data, data_resp->data_count) != Z_OK)

Index: playerc.h
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/playerc.h,v
retrieving revision 1.229.2.2
retrieving revision 1.229.2.3
diff -C2 -d -r1.229.2.2 -r1.229.2.3
*** playerc.h   10 Oct 2007 09:26:00 -0000      1.229.2.2
--- playerc.h   19 Oct 2007 21:58:55 -0000      1.229.2.3
***************
*** 472,476 ****
  
    /** List of subscribed devices */
!   struct _playerc_device_t *device[PLAYERC_MAX_DEVICES];
    int device_count;
  
--- 472,476 ----
  
    /** List of subscribed devices */
!   struct _playerc_device_t *device[PLAYER_MAX_DEVICES];
    int device_count;
  
***************
*** 3111,3115 ****
  
  /** Set the output for the speech device. */
! int playerc_speech_say (playerc_speech_t *device, const char *);
  
  
--- 3111,3115 ----
  
  /** Set the output for the speech device. */
! int playerc_speech_say (playerc_speech_t *device, char *);
  
  

Index: dev_speech.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_speech.c,v
retrieving revision 1.5.4.1
retrieving revision 1.5.4.2
diff -C2 -d -r1.5.4.1 -r1.5.4.2
*** dev_speech.c        10 Sep 2007 04:11:00 -0000      1.5.4.1
--- dev_speech.c        19 Oct 2007 21:58:55 -0000      1.5.4.2
***************
*** 91,95 ****
  
  /* Set the output for the speech device. */
! int playerc_speech_say(playerc_speech_t *device, const char *str)
  {
    player_speech_cmd_t cmd;
--- 91,95 ----
  
  /* Set the output for the speech device. */
! int playerc_speech_say(playerc_speech_t *device, char *str)
  {
    player_speech_cmd_t cmd;


-------------------------------------------------------------------------
This SF.net email is sponsored by: Splunk Inc.
Still grepping through log files to find problems?  Stop.
Now Search log events and configuration files using AJAX and a browser.
Download your FREE copy of Splunk now >> http://get.splunk.com/
_______________________________________________
Playerstage-commit mailing list
[email protected]
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to