Update of /cvsroot/playerstage/code/player/client_libs/libplayerc
In directory
sc8-pr-cvs1.sourceforge.net:/tmp/cvs-serv10946/client_libs/libplayerc
Modified Files:
client.c dev_actarray.c dev_aio.c dev_audio.c dev_blobfinder.c
dev_bumper.c dev_camera.c dev_fiducial.c dev_gps.c
dev_graphics2d.c dev_graphics3d.c dev_gripper.c dev_laser.c
dev_localize.c dev_map.c dev_opaque.c dev_planner.c
dev_pointcloud3d.c dev_rfid.c dev_simulation.c dev_sonar.c
dev_speech.c dev_speech_recognition.c dev_wifi.c playerc.h
Log Message:
applied Toby's patch to replace fixed-size arrays
Index: dev_aio.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_aio.c,v
retrieving revision 1.3
retrieving revision 1.4
diff -C2 -d -r1.3 -r1.4
*** dev_aio.c 24 Oct 2007 22:32:02 -0000 1.3
--- dev_aio.c 1 Nov 2007 22:16:16 -0000 1.4
***************
*** 73,76 ****
--- 73,77 ----
{
playerc_device_term(&device->info);
+ free(device->voltages);
free(device);
}
***************
*** 96,101 ****
(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,
--- 97,102 ----
(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.3
retrieving revision 1.4
diff -C2 -d -r1.3 -r1.4
*** dev_graphics3d.c 24 Oct 2007 22:32:02 -0000 1.3
--- dev_graphics3d.c 1 Nov 2007 22:16:16 -0000 1.4
***************
*** 88,96 ****
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;
--- 88,94 ----
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.6
retrieving revision 1.7
diff -C2 -d -r1.6 -r1.7
*** dev_rfid.c 24 Oct 2007 22:32:02 -0000 1.6
--- dev_rfid.c 1 Nov 2007 22:16:16 -0000 1.7
***************
*** 53,58 ****
void playerc_rfid_destroy(playerc_rfid_t *device)
{
! playerc_device_term(&device->info);
! free(device);
}
--- 53,64 ----
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);
}
***************
*** 76,97 ****
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;
! device->tags[i].guid_count=rfid_data->tags[i].guid_count;
! 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);
--- 82,109 ----
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.13
retrieving revision 1.14
diff -C2 -d -r1.13 -r1.14
*** dev_map.c 24 Oct 2007 22:32:02 -0000 1.13
--- dev_map.c 1 Nov 2007 22:16:16 -0000 1.14
***************
*** 80,83 ****
--- 80,84 ----
playerc_device_term(&device->info);
free(device->cells);
+ free(device->segments);
free(device);
}
***************
*** 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);
--- 131,135 ----
// Allocate space for the whole map
! device->cells = (char*)realloc(device->cells, sizeof(char) *
device->width * device->height);
assert(device->cells);
***************
*** 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);
--- 139,143 ----
#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;
data_req = (player_map_data_t *)malloc(sizeof(player_map_data_t));
--- 145,149 ----
// Tile size
! sy = sx = 640;
oi=oj=0;
data_req = (player_map_data_t *)malloc(sizeof(player_map_data_t));
***************
*** 155,159 ****
sj = MIN(sy, device->height - oj);
! memset(data_req,0,sizeof(data_req));
data_req->col = oi;
data_req->row = oj;
--- 153,157 ----
sj = MIN(sy, device->height - oj);
! memset(data_req,0,sizeof(*data_req));
data_req->col = oi;
data_req->row = oj;
***************
*** 166,170 ****
{
PLAYERC_ERR("failed to get map data");
- free(device->cells);
#if HAVE_ZLIB_H
free(unzipped_data);
--- 164,167 ----
***************
*** 175,179 ****
#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)
***************
*** 181,185 ****
PLAYERC_ERR("failed to decompress map data");
player_map_data_t_free(data_resp);
- free(device->cells);
free(unzipped_data);
free(data_req);
--- 178,181 ----
Index: dev_sonar.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_sonar.c,v
retrieving revision 1.17
retrieving revision 1.18
diff -C2 -d -r1.17 -r1.18
*** dev_sonar.c 24 Oct 2007 22:32:02 -0000 1.17
--- dev_sonar.c 1 Nov 2007 22:16:16 -0000 1.18
***************
*** 75,78 ****
--- 75,80 ----
{
playerc_device_term(&device->info);
+ free(device->scan);
+ free(device->poses);
free(device);
}
***************
*** 103,106 ****
--- 105,109 ----
{
device->scan_count = data->ranges_count;
+ device->scan = realloc(device->scan,
sizeof(*device->scan)*device->scan_count);
for (i = 0; i < device->scan_count; i++)
device->scan[i] = data->ranges[i];
***************
*** 108,134 ****
}
- #if 0
- // Process incoming pushed geometry
- void playerc_sonar_putgeom(playerc_sonar_t *device, player_msghdr_t *header,
- void *data, size_t len)
- {
- int i;
- player_sonar_geom_t * config = (player_sonar_geom_t *) data;
-
- if (len != sizeof(player_sonar_geom_t))
- {
- PLAYERC_ERR2("sonar geom has unexpected length (%d != %d)", len,
sizeof(player_sonar_geom_t));
- return;
- }
-
- device->pose_count = htons(config->pose_count);
- for (i = 0; i < device->pose_count; i++)
- {
- device->poses[i][0] = ((int16_t) ntohs(config->poses[i][0])) / 1000.0;
- device->poses[i][1] = ((int16_t) ntohs(config->poses[i][1])) / 1000.0;
- device->poses[i][2] = ((int16_t) ntohs(config->poses[i][2])) * M_PI / 180;
- }
- }
- #endif
// Get the sonar geometry. The writes the result into the proxy
--- 111,114 ----
***************
*** 147,150 ****
--- 127,132 ----
device->pose_count = config->poses_count;
+ device->poses = realloc(device->poses,
sizeof(*device->poses)*device->pose_count);
+
for (i = 0; i < device->pose_count; i++)
{
Index: dev_opaque.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_opaque.c,v
retrieving revision 1.5
retrieving revision 1.6
diff -C2 -d -r1.5 -r1.6
*** dev_opaque.c 24 Oct 2007 22:32:02 -0000 1.5
--- dev_opaque.c 1 Nov 2007 22:16:16 -0000 1.6
***************
*** 78,81 ****
--- 78,82 ----
{
playerc_device_term(&device->info);
+ free(device->data);
free(device);
}
***************
*** 104,109 ****
{
device->data_count = data->data_count;
- assert(device->data_count <= sizeof(device->data));
memcpy(device->data, data->data, device->data_count);
}
--- 105,110 ----
{
device->data_count = data->data_count;
+ device->data = realloc(device->data,
sizeof(*device->data)*device->data_count);
memcpy(device->data, data->data, device->data_count);
}
Index: dev_planner.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_planner.c,v
retrieving revision 1.7
retrieving revision 1.8
diff -C2 -d -r1.7 -r1.8
*** dev_planner.c 24 Oct 2007 22:32:02 -0000 1.7
--- dev_planner.c 1 Nov 2007 22:16:16 -0000 1.8
***************
*** 76,79 ****
--- 76,80 ----
{
playerc_device_term(&device->info);
+ free(device->waypoints);
free(device);
***************
*** 153,156 ****
--- 154,158 ----
device->waypoint_count = config->waypoints_count;
+ device->waypoints =
realloc(device->waypoints,sizeof(*device->waypoints)*device->waypoint_count);
for(i=0;i<device->waypoint_count;i++)
{
Index: dev_laser.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_laser.c,v
retrieving revision 1.44
retrieving revision 1.45
diff -C2 -d -r1.44 -r1.45
*** dev_laser.c 24 Oct 2007 22:32:02 -0000 1.44
--- dev_laser.c 1 Nov 2007 22:16:16 -0000 1.45
***************
*** 85,88 ****
--- 85,92 ----
{
playerc_device_term(&device->info);
+ free(device->ranges);
+ free(device->scan);
+ free(device->point);
+ free(device->intensity);
free(device);
}
***************
*** 102,105 ****
--- 106,116 ----
}
+ void playerc_laser_reallocate_scans(playerc_laser_t *device)
+ {
+ device->ranges = realloc(device->ranges,
sizeof(*device->ranges)*device->scan_count);
+ device->scan = realloc(device->scan,
sizeof(*device->scan)*device->scan_count);
+ device->point = realloc(device->point,
sizeof(*device->point)*device->scan_count);
+ device->intensity = realloc(device->intensity,
sizeof(*device->intensity)*device->scan_count);
+ }
// Process incoming data
***************
*** 115,119 ****
{
player_laser_data_t* scan_data = (player_laser_data_t*)data;
- assert(scan_data->ranges_count <= sizeof(device->scan) /
sizeof(device->scan[0]));
b = scan_data->min_angle;
--- 126,129 ----
***************
*** 124,127 ****
--- 134,140 ----
device->max_range = scan_data->max_range;
+ device->scan_count = scan_data->ranges_count;
+ playerc_laser_reallocate_scans(device);
+
for (i = 0; i < scan_data->ranges_count; i++)
{
***************
*** 137,141 ****
}
- device->scan_count = scan_data->ranges_count;
device->scan_id = scan_data->id;
}
--- 150,153 ----
***************
*** 153,156 ****
--- 165,171 ----
device->scan_res = db;
+ device->scan_count = scan_data->scan.ranges_count;
+ playerc_laser_reallocate_scans(device);
+
for (i = 0; i < scan_data->scan.ranges_count; i++)
{
***************
*** 166,170 ****
}
- device->scan_count = scan_data->scan.ranges_count;
device->scan_id = scan_data->scan.id;
device->robot_pose[0] = scan_data->pose.px;
--- 181,184 ----
Index: playerc.h
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/playerc.h,v
retrieving revision 1.236
retrieving revision 1.237
diff -C2 -d -r1.236 -r1.237
*** playerc.h 31 Oct 2007 01:18:42 -0000 1.236
--- playerc.h 1 Nov 2007 22:16:16 -0000 1.237
***************
*** 48,51 ****
--- 48,52 ----
#define PLAYERC_H
+ #include <netinet/in.h> // need this for struct sockaddr_in
#include <stdio.h>
***************
*** 98,117 ****
- /***************************************************************************
- * 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
-
/** @} */
--- 99,102 ----
***************
*** 482,490 ****
/** 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;
/** List of subscribed devices */
! struct _playerc_device_t *device[PLAYERC_MAX_DEVICES];
int device_count;
--- 467,475 ----
/** 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;
/** List of subscribed devices */
! struct _playerc_device_t *device[PLAYER_MAX_DEVICES];
int device_count;
***************
*** 884,888 ****
/// A bitfield of the current digital inputs.
! float voltages[PLAYER_AIO_MAX_INPUTS];
} playerc_aio_t;
--- 869,873 ----
/// A bitfield of the current digital inputs.
! float *voltages;
} playerc_aio_t;
***************
*** 937,942 ****
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;
--- 922,927 ----
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;
***************
*** 967,971 ****
/** @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. */
--- 952,956 ----
/** @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. */
***************
*** 973,977 ****
/** @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. */
--- 958,962 ----
/** @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. */
***************
*** 982,986 ****
/** @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]);
--- 967,971 ----
/** @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);
***************
*** 1160,1164 ****
/** A list of detected blobs. */
unsigned int blobs_count;
! playerc_blobfinder_blob_t blobs[PLAYER_BLOBFINDER_MAX_BLOBS];
} playerc_blobfinder_t;
--- 1145,1149 ----
/** A list of detected blobs. */
unsigned int blobs_count;
! playerc_blobfinder_blob_t *blobs;
} playerc_blobfinder_t;
***************
*** 1204,1208 ****
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. */
--- 1189,1193 ----
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. */
***************
*** 1210,1214 ****
/** Bump data: unsigned char, either boolean or code indicating corner. */
! uint8_t bumpers[PLAYERC_BUMPER_MAX_SAMPLES];
} playerc_bumper_t;
--- 1195,1199 ----
/** Bump data: unsigned char, either boolean or code indicating corner. */
! uint8_t *bumpers;
} playerc_bumper_t;
***************
*** 1279,1283 ****
correct host byte ordering.
*/
! uint8_t image[PLAYER_CAMERA_IMAGE_SIZE];
} playerc_camera_t;
--- 1264,1268 ----
correct host byte ordering.
*/
! uint8_t *image;
} playerc_camera_t;
***************
*** 1378,1382 ****
/** List of detected beacons. */
int fiducials_count;
! player_fiducial_item_t fiducials[PLAYERC_FIDUCIAL_MAX_SAMPLES];
} playerc_fiducial_t;
--- 1363,1367 ----
/** List of detected beacons. */
int fiducials_count;
! player_fiducial_item_t *fiducials;
} playerc_fiducial_t;
***************
*** 1803,1818 ****
/** 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 */
--- 1788,1803 ----
/** 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 */
***************
*** 2037,2046 ****
/** 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;
--- 2022,2031 ----
/** 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;
***************
*** 2260,2264 ****
/** Data */
! uint8_t data[PLAYER_OPAQUE_MAX_SIZE];
} playerc_opaque_t;
--- 2245,2249 ----
/** Data */
! uint8_t *data;
} playerc_opaque_t;
***************
*** 2330,2334 ****
/** 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;
--- 2315,2319 ----
/** 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;
***************
*** 2926,2930 ****
/** 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. */
--- 2911,2915 ----
/** 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. */
***************
*** 2932,2936 ****
/** Scan data: range (m). */
! double scan[PLAYERC_SONAR_MAX_SAMPLES];
} playerc_sonar_t;
--- 2917,2921 ----
/** Scan data: range (m). */
! double *scan;
} playerc_sonar_t;
***************
*** 3004,3008 ****
/** A list containing info for each link. */
! playerc_wifi_link_t links[PLAYERC_WIFI_MAX_LINKS];
int link_count;
char ip[32];
--- 2989,2993 ----
/** A list containing info for each link. */
! playerc_wifi_link_t *links;
int link_count;
char ip[32];
***************
*** 3126,3130 ****
/** 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 *);
***************
*** 3147,3154 ****
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;
--- 3132,3139 ----
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;
***************
*** 3187,3191 ****
uint32_t guid_count;
/** The Globally Unique IDentifier (GUID) of the tag. */
! uint8_t guid[PLAYERC_RFID_MAX_GUID];
} playerc_rfidtag_t;
--- 3172,3176 ----
uint32_t guid_count;
/** The Globally Unique IDentifier (GUID) of the tag. */
! uint8_t *guid;
} playerc_rfidtag_t;
***************
*** 3200,3204 ****
/** The list of RFID tags. */
! playerc_rfidtag_t tags[PLAYERC_RFID_MAX_TAGS];
} playerc_rfid_t;
--- 3185,3189 ----
/** The list of RFID tags. */
! playerc_rfidtag_t *tags;
} playerc_rfid_t;
***************
*** 3241,3245 ****
/** The list of 3D pointcloud elements. */
! playerc_pointcloud3d_element_t points[PLAYERC_POINTCLOUD3D_MAX_POINTS];
} playerc_pointcloud3d_t;
--- 3226,3230 ----
/** 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.16
retrieving revision 1.17
diff -C2 -d -r1.16 -r1.17
*** dev_simulation.c 24 Oct 2007 22:32:02 -0000 1.16
--- dev_simulation.c 1 Nov 2007 22:16:16 -0000 1.17
***************
*** 108,113 ****
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;
--- 108,112 ----
memset(&cmd, 0, sizeof(cmd));
! cmd.name = name;
cmd.name_count = strlen(cmd.name) + 1;
cmd.pose.px = gx;
***************
*** 124,141 ****
double *x, double *y, double *a)
{
! player_simulation_pose2d_req_t cfg, *resp;
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,
PLAYER_SIMULATION_REQ_GET_POSE2D,
! &cfg, (void**)&resp) < 0)
return (-1);
! *x = resp->pose.px;
! *y = resp->pose.py;
! *a = resp->pose.pa;
! player_simulation_pose2d_req_t_free(resp);
return 0;
}
--- 123,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;
}
***************
*** 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;
--- 147,151 ----
memset(&cmd, 0, sizeof(cmd));
! cmd.name = name;
cmd.name_count = strlen(cmd.name) + 1;
cmd.pose.px = gx;
***************
*** 167,188 ****
double *x, double *y, double *z, double *roll, double *pitch,
double *yaw, double *time)
{
! player_simulation_pose3d_req_t cfg, *resp;
! 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,
PLAYER_SIMULATION_REQ_GET_POSE3D,
! &cfg, (void**)&resp) < 0)
return (-1);
! *x = resp->pose.px;
! *y = resp->pose.py;
! *z = resp->pose.pz;
! *pitch = resp->pose.ppitch;
! *roll = resp->pose.proll;
! *yaw = resp->pose.pyaw;
! *time = resp->simtime;
! player_simulation_pose3d_req_t_free(resp);
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;
}
***************
*** 198,217 ****
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;
--- 195,205 ----
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;
***************
*** 231,250 ****
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,
--- 219,230 ----
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_blobfinder.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_blobfinder.c,v
retrieving revision 1.14
retrieving revision 1.15
diff -C2 -d -r1.14 -r1.15
*** dev_blobfinder.c 24 Oct 2007 22:32:02 -0000 1.14
--- dev_blobfinder.c 1 Nov 2007 22:16:16 -0000 1.15
***************
*** 76,79 ****
--- 76,80 ----
{
playerc_device_term(&device->info);
+ free(device->blobs);
free(device);
}
***************
*** 108,113 ****
// 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);
--- 109,114 ----
// 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.18
retrieving revision 1.19
diff -C2 -d -r1.18 -r1.19
*** dev_localize.c 24 Oct 2007 22:32:02 -0000 1.18
--- dev_localize.c 1 Nov 2007 22:16:16 -0000 1.19
***************
*** 74,80 ****
void playerc_localize_destroy(playerc_localize_t *device)
{
- if (device->map_cells)
- free(device->map_cells);
playerc_device_term(&device->info);
free(device);
return;
--- 74,81 ----
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;
***************
*** 104,119 ****
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;
--- 105,114 ----
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;
***************
*** 167,180 ****
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;
--- 162,169 ----
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.4
diff -C2 -d -r1.3 -r1.4
*** dev_speech_recognition.c 9 Jun 2007 02:59:12 -0000 1.3
--- dev_speech_recognition.c 1 Nov 2007 22:16:16 -0000 1.4
***************
*** 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_fiducial.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_fiducial.c,v
retrieving revision 1.18
retrieving revision 1.19
diff -C2 -d -r1.18 -r1.19
*** dev_fiducial.c 24 Oct 2007 22:32:02 -0000 1.18
--- dev_fiducial.c 1 Nov 2007 22:16:16 -0000 1.19
***************
*** 86,103 ****
void* generic )
{
if( header->type == PLAYER_MSGTYPE_DATA &&
header->subtype == PLAYER_FIDUCIAL_DATA_SCAN )
! {
! player_fiducial_data_t* data = (player_fiducial_data_t*)generic;
!
! device->fiducials_count = data->fiducials_count;
! int i;
! for (i = 0; i < device->fiducials_count; i++)
! {
! player_fiducial_item_t *fiducial = data->fiducials + i;
! device->fiducials[i] = *fiducial;
/* device->fiducials[i].id = fiducial->id;
--- 86,103 ----
void* generic )
{
+ int i;
if( header->type == PLAYER_MSGTYPE_DATA &&
header->subtype == PLAYER_FIDUCIAL_DATA_SCAN )
! {
! player_fiducial_data_t* data = (player_fiducial_data_t*)generic;
! device->fiducials_count = data->fiducials_count;
! device->fiducials = realloc(device->fiducials,
sizeof(device->fiducials)*device->fiducials_count);
! for (i = 0; i < device->fiducials_count; i++)
! {
! player_fiducial_item_t *fiducial = data->fiducials + i;
! device->fiducials[i] = *fiducial;
/* device->fiducials[i].id = fiducial->id;
***************
*** 121,126 ****
device->fiducials[i].bearing = atan2(device->fiducials[i].pos[1],
device->fiducials[i].pos[0]);
device->fiducials[i].orient = device->fiducials[i].rot[2];*/
- }
}
else
--- 121,126 ----
device->fiducials[i].bearing = atan2(device->fiducials[i].pos[1],
device->fiducials[i].pos[0]);
device->fiducials[i].orient = device->fiducials[i].rot[2];*/
}
+ }
else
***************
*** 130,141 ****
- // Process incoming geom
- void playerc_fiducial_putgeom(playerc_fiducial_t *device, player_msghdr_t
*header,
- player_fiducial_geom_t *data, size_t len)
- {
- PLAYERC_WARN( "playerc_fiducial_putgeom is not yet implemented" );
-
- }
-
// Get the fiducial geometry. The writes the result into the proxy
// rather than returning it to the caller.
--- 130,133 ----
Index: dev_speech.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_speech.c,v
retrieving revision 1.5
retrieving revision 1.6
diff -C2 -d -r1.5 -r1.6
*** dev_speech.c 12 Feb 2006 00:54:38 -0000 1.5
--- dev_speech.c 1 Nov 2007 22:16:16 -0000 1.6
***************
*** 91,105 ****
/* Set the output for the speech device. */
! int playerc_speech_say(playerc_speech_t *device, const char *str)
{
player_speech_cmd_t cmd;
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,
--- 91,101 ----
/* Set the output for the speech device. */
! int playerc_speech_say(playerc_speech_t *device, char *str)
{
player_speech_cmd_t cmd;
memset(&cmd, 0, sizeof(cmd));
! cmd.string = str;
! cmd.string_count = strlen(str) + 1;
return playerc_client_write(device->info.client,
Index: dev_actarray.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_actarray.c,v
retrieving revision 1.12
retrieving revision 1.13
diff -C2 -d -r1.12 -r1.13
*** dev_actarray.c 20 Sep 2007 23:15:47 -0000 1.12
--- dev_actarray.c 1 Nov 2007 22:16:16 -0000 1.13
***************
*** 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;
***************
*** 112,134 ****
if((result = playerc_client_request(device->info.client, &device->info,
! PLAYER_ACTARRAY_REQ_GET_GEOM, NULL, (void**)&geom)) < 0)
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;
--- 111,121 ----
if((result = playerc_client_request(device->info.client, &device->info,
! PLAYER_ACTARRAY_REQ_GET_GEOM, NULL, (void*)&geom)) < 0)
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;
***************
*** 153,163 ****
// 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,
--- 140,150 ----
// 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,
***************
*** 183,193 ****
// 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,
--- 170,180 ----
// 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,
***************
*** 225,235 ****
// 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,
--- 212,222 ----
// 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_pointcloud3d.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_pointcloud3d.c,v
retrieving revision 1.3
retrieving revision 1.4
diff -C2 -d -r1.3 -r1.4
*** dev_pointcloud3d.c 24 Oct 2007 22:32:02 -0000 1.3
--- dev_pointcloud3d.c 1 Nov 2007 22:16:16 -0000 1.4
***************
*** 53,56 ****
--- 53,57 ----
{
playerc_device_term (&device->info);
+ free (device->points);
free (device);
***************
*** 80,84 ****
{
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);
--- 81,86 ----
{
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_bumper.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_bumper.c,v
retrieving revision 1.8
retrieving revision 1.9
diff -C2 -d -r1.8 -r1.9
*** dev_bumper.c 24 Oct 2007 22:32:02 -0000 1.8
--- dev_bumper.c 1 Nov 2007 22:16:16 -0000 1.9
***************
*** 79,82 ****
--- 79,84 ----
{
playerc_device_term(&device->info);
+ free(device->poses);
+ free(device->bumpers);
free(device);
}
***************
*** 107,110 ****
--- 109,113 ----
player_bumper_data_t * bdata = (player_bumper_data_t *) data;
device->bumper_count = bdata->bumpers_count;
+ device->bumpers =
(uint8_t*)realloc(device->bumpers,sizeof(uint8_t)*device->bumper_count);
// data is array of bytes, either as boolean or coded for bumper corner
***************
*** 118,121 ****
--- 121,125 ----
device->pose_count = bgeom->bumper_def_count;
+ device->poses =
realloc(device->poses,sizeof(player_bumper_define_t)*device->pose_count);
for (i = 0; i < device->pose_count; i++)
{
***************
*** 138,141 ****
--- 142,146 ----
return -1;
device->pose_count = config->bumper_def_count;
+ device->poses =
realloc(device->poses,sizeof(player_bumper_define_t)*device->pose_count);
for (i = 0; i < device->pose_count; i++)
{
Index: client.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/client.c,v
retrieving revision 1.83
retrieving revision 1.84
diff -C2 -d -r1.83 -r1.84
*** client.c 24 Oct 2007 22:32:02 -0000 1.83
--- client.c 1 Nov 2007 22:16:16 -0000 1.84
***************
*** 75,91 ****
static int init_done;
- // TODO: get rid of this structure
- // Player message structure for subscibing to devices. This one is
- // easier to use than the one defined in messages.h.
- /*
- typedef struct
- {
- uint16_t subtype;
- uint16_t device;
- uint16_t index;
- uint8_t access;
- } __attribute__ ((packed)) playerc_msg_subscribe_t;
- */
-
void dummy(int sig)
{
--- 75,78 ----
Index: dev_camera.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_camera.c,v
retrieving revision 1.16
retrieving revision 1.17
diff -C2 -d -r1.16 -r1.17
*** dev_camera.c 24 Oct 2007 22:32:02 -0000 1.16
--- dev_camera.c 1 Nov 2007 22:16:16 -0000 1.17
***************
*** 83,86 ****
--- 83,87 ----
{
playerc_device_term(&device->info);
+ free(device->image);
free(device);
}
***************
*** 115,118 ****
--- 116,120 ----
device->compression = data->compression;
device->image_count = data->image_count;
+ device->image = realloc(device->image,
sizeof(device->image[0])*device->image_count);
assert(device->image_count <= sizeof(device->image));
***************
*** 145,148 ****
--- 147,151 ----
// Copy uncompress image
device->image_count = dst_size;
+ device->image = realloc(device->image,
sizeof(device->image[0])*device->image_count);
assert(dst_size <= sizeof device->image);
memcpy(device->image, dst, dst_size);
Index: dev_graphics2d.c
===================================================================
RCS file:
/cvsroot/playerstage/code/player/client_libs/libplayerc/dev_graphics2d.c,v
retrieving revision 1.9
retrieving revision 1.10
diff -C2 -d -r1.9 -r1.10
*** dev_graphics2d.c 24 Oct 2007 22:32:02 -0000 1.9
--- dev_graphics2d.c 1 Nov 2007 22:16:16 -0000 1.10
***************
*** 86,93 ****
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;
--- 86,91 ----
player_graphics2d_cmd_points_t cmd;
cmd.points_count = count;
! cmd.points= pts;
cmd.color = device->color;
***************
*** 104,112 ****
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,
--- 102,108 ----
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,
***************
*** 123,130 ****
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;
--- 119,124 ----
player_graphics2d_cmd_polygon_t cmd;
cmd.points_count = count;
! cmd.points = pts;
cmd.color = device->color;
cmd.filled = filled;
Index: dev_wifi.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_wifi.c,v
retrieving revision 1.15
retrieving revision 1.16
diff -C2 -d -r1.15 -r1.16
*** dev_wifi.c 24 Oct 2007 22:32:02 -0000 1.15
--- dev_wifi.c 1 Nov 2007 22:16:16 -0000 1.16
***************
*** 74,77 ****
--- 74,78 ----
{
playerc_device_term(&self->info);
+ free(self->links);
free(self);
}
***************
*** 96,104 ****
player_wifi_data_t *data, size_t len)
{
! int i,j;
if((header->type == PLAYER_MSGTYPE_DATA))
{
device->link_count = data->links_count;
// copy all available link information
--- 97,106 ----
player_wifi_data_t *data, size_t len)
{
! int i;
if((header->type == PLAYER_MSGTYPE_DATA))
{
device->link_count = data->links_count;
+ device->links = realloc(device->links,
sizeof(*device->links)*device->link_count);
// copy all available link information
Index: dev_audio.c
===================================================================
RCS file: /cvsroot/playerstage/code/player/client_libs/libplayerc/dev_audio.c,v
retrieving revision 1.7
retrieving revision 1.8
diff -C2 -d -r1.7 -r1.8
*** dev_audio.c 20 Sep 2007 23:15:47 -0000 1.7
--- dev_audio.c 1 Nov 2007 22:16:16 -0000 1.8
***************
*** 66,69 ****
--- 66,70 ----
{
playerc_device_term(&device->info);
+ free(device->wav_data.data);
free(device);
}
-------------------------------------------------------------------------
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