From: <th...@us...> - 2008-06-16 19:57:39
|
Revision: 6612 http://playerstage.svn.sourceforge.net/playerstage/?rev=6612&view=rev Author: thjc Date: 2008-06-16 19:57:46 -0700 (Mon, 16 Jun 2008) Log Message: ----------- merged [6566] from 2-1 (applied patch [ 1982705 ] Player-2.1.0rc2: QNX Neutrino 6.2.0 compatibility bigpatch) Modified Paths: -------------- code/player/trunk/client_libs/libplayerc/client.c code/player/trunk/client_libs/libplayerc/dev_audio.c code/player/trunk/client_libs/libplayerc/dev_blackboard.c code/player/trunk/client_libs/libplayerc/dev_blinkenlight.c code/player/trunk/client_libs/libplayerc/dev_camera.c code/player/trunk/client_libs/libplayerc/dev_laser.c code/player/trunk/client_libs/libplayerc/test/test_blinkenlight.c code/player/trunk/client_libs/libplayerc/test/test_dio.c code/player/trunk/client_libs/libplayerc/test/test_graphics2d.c code/player/trunk/client_libs/libplayerc/test/test_graphics3d.c code/player/trunk/client_libs/libplayerc/test/test_simulation.c code/player/trunk/client_libs/libplayerc/test/test_speech.c code/player/trunk/examples/libplayerc/vmap.c code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c code/player/trunk/libplayercore/devicetable.cc code/player/trunk/libplayercore/driver.h code/player/trunk/replace/poll.c code/player/trunk/server/drivers/blobfinder/cmvision/cmvision.cc code/player/trunk/server/drivers/gps/garminnmea.cc code/player/trunk/server/drivers/imu/MTComm.cpp code/player/trunk/server/drivers/laser/RS4LeuzeLaserDriver.cc code/player/trunk/server/drivers/laser/RS4Leuze_laser.cc code/player/trunk/server/drivers/laser/RS4Leuze_laser.h code/player/trunk/server/drivers/laser/bumper2laser.cc code/player/trunk/server/drivers/laser/pbs_driver.cc code/player/trunk/server/drivers/laser/sicklms200.cc code/player/trunk/server/drivers/laser/urglaserdriver.cc code/player/trunk/server/drivers/localization/fakelocalize.cc code/player/trunk/server/drivers/map/mapcspace.cc code/player/trunk/server/drivers/mixed/p2os/p2os.cc code/player/trunk/server/drivers/mixed/rflex/rflex-io.cc code/player/trunk/server/drivers/planner/wavefront/plan_plan.c code/player/trunk/server/drivers/position/ascension/flockofbirds.cc code/player/trunk/server/drivers/position/nav200/nav200.h code/player/trunk/server/drivers/position/roboteq/roboteq.cc code/player/trunk/server/drivers/ptz/canonvcc4.cc code/player/trunk/server/drivers/ptz/ptu46.cc code/player/trunk/server/drivers/rfid/insideM300.cc code/player/trunk/server/drivers/rfid/rfi341_protocol.cc code/player/trunk/server/drivers/shell/readlog.cc code/player/trunk/server/drivers/wifi/aodv.cc code/player/trunk/utils/logsplitter/logsplitter.c Modified: code/player/trunk/client_libs/libplayerc/client.c =================================================================== --- code/player/trunk/client_libs/libplayerc/client.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/client.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -56,7 +56,6 @@ #include <netinet/tcp.h> #endif #include <sys/socket.h> -#include <sys/poll.h> #include <netdb.h> // for gethostbyname() #include <errno.h> #include <sys/time.h> @@ -64,8 +63,11 @@ #include <unistd.h> #include <fcntl.h> - +#ifdef HAVE_POLL +#include <sys/poll.h> +#else #include <replace/replace.h> // for poll(2) +#endif #include "playerc.h" #include "error.h" @@ -319,9 +321,11 @@ "unexpected exit may result"); else { +#ifdef SA_RESTART sigact.sa_handler = dummy; sigact.sa_flags &= ~SA_RESTART; if(sigaction(SIGALRM, &sigact, NULL) != 0) +#endif PLAYER_WARN("failed to set SIGALRM action data; " "unexpected exit may result"); } @@ -337,9 +341,11 @@ "unexpected exit may result"); /* Restore normal SIGALRM behavior */ +#ifdef SA_RESTART sigact.sa_handler = SIG_DFL; sigact.sa_flags |= SA_RESTART; if(sigaction(SIGALRM, &sigact, NULL) != 0) +#endif PLAYER_WARN("failed to reset SIGALRM action data; " "unexpected behavior may result"); Modified: code/player/trunk/client_libs/libplayerc/dev_audio.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_audio.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/dev_audio.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -87,8 +87,8 @@ { if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_AUDIO_DATA_WAV_REC)) { + player_audio_wav_t * wdata = (player_audio_wav_t *) data; assert(header->size > 0); - player_audio_wav_t * wdata = (player_audio_wav_t *) data; device->wav_data.data_count = wdata->data_count; if (device->wav_data.data != NULL) free (device->wav_data.data); @@ -102,22 +102,22 @@ } else if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_AUDIO_DATA_SEQ)) { + player_audio_seq_t * sdata = (player_audio_seq_t *) data; assert(header->size > 0); - player_audio_seq_t * sdata = (player_audio_seq_t *) data; device->seq_data.tones_count = sdata->tones_count; memcpy(device->seq_data.tones, sdata->tones, sdata->tones_count * sizeof(device->seq_data.tones[0])); } else if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_AUDIO_DATA_MIXER_CHANNEL)) { + player_audio_mixer_channel_list_t * wdata = (player_audio_mixer_channel_list_t *) data; assert(header->size > 0); - player_audio_mixer_channel_list_t * wdata = (player_audio_mixer_channel_list_t *) data; device->mixer_data.channels_count = wdata->channels_count; memcpy(device->mixer_data.channels, wdata->channels, wdata->channels_count * sizeof(device->mixer_data.channels[0])); } else if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_AUDIO_DATA_STATE)) { + player_audio_state_t *sdata = (player_audio_state_t *) data; assert(header->size > 0); - player_audio_state_t *sdata = (player_audio_state_t *) data; device->state = sdata->state; } else Modified: code/player/trunk/client_libs/libplayerc/dev_blackboard.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_blackboard.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/dev_blackboard.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -153,10 +153,12 @@ char *playerc_unpack_blackboard_entry_string(const player_blackboard_entry_t *entry) { + char * result; + assert(entry->type == PLAYERC_BLACKBOARD_DATA_TYPE_COMPLEX); assert(entry->subtype == PLAYERC_BLACKBOARD_DATA_SUBTYPE_STRING); - char *result = malloc(entry->data_count); + result = malloc(entry->data_count); assert(result); memcpy(result, entry->data, entry->data_count); @@ -164,10 +166,11 @@ } int playerc_unpack_blackboard_entry_int(const player_blackboard_entry_t *entry) { + int result = 0; + assert(entry->type == PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE); assert(entry->subtype == PLAYERC_BLACKBOARD_DATA_SUBTYPE_INT); - int result = 0; memcpy(&result, entry->data, entry->data_count); return result; @@ -175,10 +178,11 @@ double playerc_unpack_blackboard_entry_double(const player_blackboard_entry_t *entry) { + double result = 0.0; + assert(entry->type == PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE); assert(entry->subtype == PLAYERC_BLACKBOARD_DATA_SUBTYPE_DOUBLE); - double result = 0.0; memcpy(&result, entry->data, entry->data_count); return result; Modified: code/player/trunk/client_libs/libplayerc/dev_blinkenlight.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_blinkenlight.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/dev_blinkenlight.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -66,8 +66,6 @@ player_msghdr_t *header, void* data, size_t len) { - //int i = 0; - if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_BLINKENLIGHT_DATA_STATE)) { Modified: code/player/trunk/client_libs/libplayerc/dev_camera.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_camera.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/dev_camera.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -130,36 +130,36 @@ void playerc_camera_decompress(playerc_camera_t *device) { if (device->compression == PLAYER_CAMERA_COMPRESS_RAW) + { return; - + } else + { #if HAVE_JPEG - int dst_size; - unsigned char *dst; + // Create a temp buffer + int dst_size = device->width * device->height * device->bpp / 8; + unsigned char * dst = malloc(dst_size); - // Create a temp buffer - dst_size = device->width * device->height * device->bpp / 8; - dst = malloc(dst_size); + // Decompress into temp buffer + jpeg_decompress(dst, dst_size, device->image, device->image_count); - // Decompress into temp buffer - jpeg_decompress(dst, dst_size, device->image, device->image_count); + // Copy uncompress image + device->image_count = dst_size; + device->image = realloc(device->image, sizeof(device->image[0])*device->image_count); + if (device->image) + memcpy(device->image, dst, dst_size); + else + PLAYERC_ERR1("failed to allocate memory for image, needed %ld bytes\n", sizeof(device->image[0])*device->image_count); + free(dst); - // Copy uncompress image - device->image_count = dst_size; - device->image = realloc(device->image, sizeof(device->image[0])*device->image_count); - if (device->image) - memcpy(device->image, dst, dst_size); - else - PLAYERC_ERR1("failed to allocate memory for image, needed %ld bytes\n", sizeof(device->image[0])*device->image_count); - free(dst); + // Pixels are now raw + device->compression = PLAYER_CAMERA_COMPRESS_RAW; - // Pixels are now raw - device->compression = PLAYER_CAMERA_COMPRESS_RAW; - #else - PLAYERC_ERR("JPEG decompression support was not included at compile-time"); + PLAYERC_ERR("JPEG decompression support was not included at compile-time"); #endif + } return; } Modified: code/player/trunk/client_libs/libplayerc/dev_laser.c =================================================================== --- code/player/trunk/client_libs/libplayerc/dev_laser.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/dev_laser.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -307,6 +307,7 @@ void playerc_laser_printout( playerc_laser_t * device, const char* prefix ) { + int i; if( prefix ) printf( "%s: ", prefix ); @@ -316,7 +317,6 @@ device->scan_count ); printf( "# ranges\n" ); - int i; for( i=0; i<device->scan_count; i++ ) printf( "%.3f ", device->ranges[i] ); puts( "" ); Modified: code/player/trunk/client_libs/libplayerc/test/test_blinkenlight.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_blinkenlight.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_blinkenlight.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -13,9 +13,13 @@ // Basic test for an dio device. int test_blinkenlight(playerc_client_t *client, int index) { - //int t; - //void *rdevice; playerc_blinkenlight_t *device; + unsigned long shortsleep = 200000L; + unsigned long longsleep = 500000L; + int u; + int lightnum; + double rate; + double duty; printf("device [blinkenlight] index [%d]\n", index); @@ -27,18 +31,18 @@ return -1; } PASS(); - + /* for (t = 0; t < 5; t++) { */ /* TEST1("reading light state (attempt %d)", t); */ - + /* do */ /* rdevice = playerc_client_read(client); */ /* while (rdevice == client); */ - + /* if (rdevice == device) */ /* { */ /* PASS(); */ - + /* printf("blinkenlight: enable %u color (%hhX,%hhX,%hhX) period %.3f duty %.3f\n", */ /* device->enable, */ /* device->red, */ @@ -46,7 +50,7 @@ /* device->blue, */ /* device->period, */ /* device->duty ); */ - + /* } */ /* else { */ /* //printf("error: %s", playerc_error_str()); */ @@ -54,36 +58,31 @@ /* break; */ /* } */ /* } */ - - unsigned long shortsleep = 200000L; - unsigned long longsleep = 500000L; - + TEST("Turning light on"); - if (playerc_blinkenlight_enable( device, 1 ) != 0) + if (playerc_blinkenlight_enable( device, 1 ) != 0) FAIL(); PASS(); usleep( longsleep ); - + TEST("Turning light off"); - if (playerc_blinkenlight_enable( device, 0 ) != 0) + if (playerc_blinkenlight_enable( device, 0 ) != 0) FAIL(); PASS(); usleep( longsleep ); TEST("Turning light on"); - if (playerc_blinkenlight_enable( device, 1 ) != 0) + if (playerc_blinkenlight_enable( device, 1 ) != 0) FAIL(); PASS(); usleep( longsleep ); - - int u; TEST( "Setting colors RED"); for( u=5; u<256; u+=50 ) - { + { for( index=0; index<LIGHTCOUNT; index++ ) { - if (playerc_blinkenlight_color(device, index, u,0,0 ) != 0) + if (playerc_blinkenlight_color(device, index, u,0,0 ) != 0) { FAIL(); break; @@ -93,14 +92,12 @@ } PASS(); - int lightnum; - TEST( "Setting colors GREEN"); for( u=5; u<256; u+=50 ) - { + { for( lightnum=0; lightnum<LIGHTCOUNT; lightnum++ ) { - if (playerc_blinkenlight_color(device, lightnum, 0,u,0 ) != 0) + if (playerc_blinkenlight_color(device, lightnum, 0,u,0 ) != 0) { FAIL(); break; @@ -109,13 +106,13 @@ } } PASS(); - + TEST( "Setting colors BLUE"); for( u=5; u<256; u+=50 ) - { + { for( lightnum=0; lightnum<LIGHTCOUNT; lightnum++ ) { - if (playerc_blinkenlight_color(device, lightnum, 0,0,u ) != 0) + if (playerc_blinkenlight_color(device, lightnum, 0,0,u ) != 0) { FAIL(); break; @@ -124,13 +121,13 @@ } } PASS(); - + TEST( "Setting colors R+G+B"); for( u=5; u<256; u+=50 ) - { + { for( lightnum=0; lightnum<LIGHTCOUNT; lightnum++ ) { - if (playerc_blinkenlight_color(device, lightnum, u,u,u ) != 0) + if (playerc_blinkenlight_color(device, lightnum, u,u,u ) != 0) { FAIL(); break; @@ -142,14 +139,14 @@ TEST( "Setting colors randomly"); for( u=0; u<10; u++ ) - { + { for( lightnum=0; lightnum<LIGHTCOUNT; lightnum++ ) { - if (playerc_blinkenlight_color(device, + if (playerc_blinkenlight_color(device, lightnum, random()%255, random()%255, - random()%255) != 0) + random()%255) != 0) { FAIL(); break; @@ -161,14 +158,11 @@ usleep(longsleep); //some time to see the effect TEST("Varying blink rate"); - - double rate; - double duty; - + for( rate=3; rate<=10; rate++ ) for( duty=0.1; rate<=1.0; rate+=0.1 ) for( lightnum=0; lightnum<6; lightnum++ ) - if (playerc_blinkenlight_blink( device, lightnum, rate, duty ) != 0) + if (playerc_blinkenlight_blink( device, lightnum, rate, duty ) != 0) { FAIL(); break; @@ -176,17 +170,17 @@ PASS(); TEST("Turning light off"); - if (playerc_blinkenlight_enable( device, 0 ) != 0) + if (playerc_blinkenlight_enable( device, 0 ) != 0) FAIL(); PASS(); - + TEST("unsubscribing"); if (playerc_blinkenlight_unsubscribe(device) != 0) FAIL(); PASS(); - + playerc_blinkenlight_destroy(device); - + return 0; } Modified: code/player/trunk/client_libs/libplayerc/test/test_dio.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_dio.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_dio.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -15,6 +15,9 @@ int t; void *rdevice; playerc_dio_t *device; + int i; + unsigned int do_value; + const unsigned int do_count = 8; printf("device [dio] index [%d]\n", index); @@ -39,7 +42,6 @@ printf("dio: [%8.3f] MSB...LSB:[ ", device->info.datatime); - int i=0; //printf("%d : ",device->digin); for (i=0 ; i != device->count ; i++) { @@ -62,9 +64,7 @@ } - unsigned int do_value=0; - const unsigned int do_count=8; - + do_value = 0; for (t = 0; t < 5; t++) { TEST1("writing data (attempt %d)", t); @@ -81,7 +81,7 @@ } //turn everything off: - do_value=0; + do_value = 0; playerc_dio_set_output(device, do_count, do_value ); @@ -96,4 +96,3 @@ return 0; } - Modified: code/player/trunk/client_libs/libplayerc/test/test_graphics2d.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_graphics2d.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_graphics2d.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -19,6 +19,10 @@ /* int t; void *rdevice;*/ playerc_graphics2d_t *device; + int p; + double r; + player_point_2d_t pts[RAYS]; + player_color_t col; printf("device [graphics2d] index [%d]\n", index); @@ -32,15 +36,10 @@ } PASS(); - - player_point_2d_t pts[RAYS]; - - double r; for( r=0; r<1.0; r+=0.05 ) { TEST("drawing points"); - - int p; + for( p=0; p<RAYS; p++ ) { pts[p].px = r * cos(p * M_PI/(RAYS/2)); @@ -56,7 +55,6 @@ } TEST("changing color"); - player_color_t col; col.red = 0; col.green = 255; col.blue = 0; @@ -92,8 +90,6 @@ for( r=1.0; r>0; r-=0.1 ) { TEST("drawing polygon"); - - player_point_2d_t pts[4]; pts[0].px = -r; pts[0].py = -r; pts[1].px = r; Modified: code/player/trunk/client_libs/libplayerc/test/test_graphics3d.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_graphics3d.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_graphics3d.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -19,6 +19,11 @@ /* int t; void *rdevice;*/ playerc_graphics3d_t *device; + player_color_t col; + player_point_3d_t pts[RAYS]; + player_point_3d_t pt; + int p; + double r; printf("device [graphics3d] index [%d]\n", index); @@ -32,9 +37,7 @@ } PASS(); - TEST("changing color"); - player_color_t col; col.red = 0; col.green = 0; col.blue = 255; @@ -44,15 +47,11 @@ FAIL(); else PASS(); - - player_point_3d_t pts[RAYS]; - - double r; + for( r=0; r<1.0; r+=0.05 ) { TEST("drawing line loop"); - - int p; + for( p=0; p<RAYS; p++ ) { pts[p].px = 5 * r * cos(p * M_PI/(RAYS/2)); @@ -107,7 +106,6 @@ for( r=0; r<300; r++ ) { - player_point_3d_t pt; pt.px = fmod( rand(), 100 ) / 50.0 - 1.0; pt.py = fmod( rand(), 100 ) / 50.0 - 1.0; pt.pz = fmod( rand(), 100 ) / 30; Modified: code/player/trunk/client_libs/libplayerc/test/test_simulation.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_simulation.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_simulation.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -17,6 +17,7 @@ double x,y,a; //void *rdevice; playerc_simulation_t *device; + int fr, col; printf("device [simulation] index [%d]\n", index); @@ -55,13 +56,13 @@ FAIL(); TEST("setting property \"fiducial_return\" for model robot1 to 42"); - int fr = 42; + fr = 42; if (playerc_simulation_set_property(device, "robot1", "_mp_fiducial_return", &fr, sizeof(fr) ) == 0) PASS(); else FAIL(); - int col = 0xFF00; + col = 0xFF00; TEST("setting property \"color\" for model robot1 to 0x00FF00 (green)"); if (playerc_simulation_set_property(device, "robot1", "_mp_color", &col, sizeof(col) ) == 0) PASS(); Modified: code/player/trunk/client_libs/libplayerc/test/test_speech.c =================================================================== --- code/player/trunk/client_libs/libplayerc/test/test_speech.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/client_libs/libplayerc/test/test_speech.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -16,6 +16,8 @@ //int t; //void *rdevice; playerc_speech_t *device; + char text[]="Hello World!"; + char text2[]="12345678901234567890123456789012345678901234567890"; printf("device [speech] index [%d]\n", index); @@ -32,8 +34,6 @@ TEST1("writing data (attempt %d)",1); - char text[]="Hello World!"; - if (playerc_speech_say(device, text ) != 0) { FAIL(); } else { @@ -43,8 +43,6 @@ TEST1("writing data (attempt %d)",2); - char text2[]="12345678901234567890123456789012345678901234567890"; - TEST1("Printing: %s",text2); if (playerc_speech_say(device, text2 ) != 0) { FAIL(); Modified: code/player/trunk/examples/libplayerc/vmap.c =================================================================== --- code/player/trunk/examples/libplayerc/vmap.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/examples/libplayerc/vmap.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -9,6 +9,7 @@ { playerc_client_t* client = NULL; playerc_vectormap_t* vmap = NULL; + GEOSGeom g; printf("Creating client\n"); client = playerc_client_create(NULL, "localhost", 6665); @@ -56,7 +57,7 @@ PrintLayerData(vmap); printf("Getting feature data\n"); - GEOSGeom g = playerc_vectormap_get_feature_data(vmap, 0, 0); + g = playerc_vectormap_get_feature_data(vmap, 0, 0); if (g == NULL) { printf("Error getting feature data\n"); @@ -75,16 +76,16 @@ void PrintMapInfo(playerc_vectormap_t* vmap) { + player_extent2d_t extent = vmap->extent; printf("MapInfo\n"); printf("srid = %d\nlayer_count = %d\n", vmap->srid, vmap->layers_count); - player_extent2d_t extent = vmap->extent; printf("extent = (%f %f, %f %f)\n", extent.x0, extent.y0, extent.x1, extent.y1); } void PrintLayerInfo(playerc_vectormap_t* vmap) { + player_extent2d_t extent = vmap->layers_info[0]->extent; printf("LayerInfo\n"); - player_extent2d_t extent = vmap->layers_info[0]->extent; printf("extent = (%f %f, %f %f)\n", extent.x0, extent.y0, extent.x1, extent.y1); printf("name = %s\n", vmap->layers_info[0]->name); } Modified: code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c =================================================================== --- code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -56,8 +56,8 @@ { if((header->type == PLAYER_MSGTYPE_DATA) && (header->subtype == PLAYER_EXAMPLE_DATA_EXAMPLE)) { + player_eginterf_data_t *stuffData = (player_eginterf_data_t *) data; assert(header->size > 0); - player_eginterf_data_t *stuffData = (player_eginterf_data_t *) data; if (device->stuff != NULL) free (device->stuff); if ((device->stuff = (double*) malloc (stuffData->stuff_count)) == NULL) Modified: code/player/trunk/libplayercore/devicetable.cc =================================================================== --- code/player/trunk/libplayercore/devicetable.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/libplayercore/devicetable.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -43,6 +43,7 @@ * class to keep track of available devices. */ #include <string.h> // for strncpy(3) +#include <stdlib.h> // for atoi(3) #include <libplayercore/error.h> #include <libplayercore/devicetable.h> Modified: code/player/trunk/libplayercore/driver.h =================================================================== --- code/player/trunk/libplayercore/driver.h 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/libplayercore/driver.h 2008-06-17 02:57:46 UTC (rev 6612) @@ -54,7 +54,6 @@ #include <libplayercore/player.h> #include <libplayercore/property.h> -#include <map> using namespace std; /** Modified: code/player/trunk/replace/poll.c =================================================================== --- code/player/trunk/replace/poll.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/replace/poll.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -33,6 +33,28 @@ #include <sys/param.h> #include <unistd.h> +/* *-*-nto-qnx doesn't define this constant in the system headers */ +#ifndef NFDBITS +#define NFDBITS (8 * sizeof(unsigned long)) +#endif + +/* Macros for counting and rounding. */ +#ifndef howmany +#define howmany(x, y) (((x) + ((y) - 1)) / (y)) +#endif +#ifndef powerof2 +#define powerof2(x) ((((x) - 1) & (x)) == 0) +#endif +#ifndef roundup +#ifdef __GNUC__ +#define roundup(x, y) (__builtin_constant_p (y) && powerof2 (y) \ + ? (((x) + (y) - 1) & ~((y) - 1)) \ + : ((((x) + ((y) - 1)) / (y)) * (y))) +#else +#define roundup(x, y) ((((x) + ((y) - 1)) / (y)) * (y)) +#endif +#endif + /* Poll the file descriptors described by the NFDS structures starting at FDS. If TIMEOUT is nonzero and not -1, allow TIMEOUT milliseconds for an event to occur; if TIMEOUT is -1, block until an event occurs. Modified: code/player/trunk/server/drivers/blobfinder/cmvision/cmvision.cc =================================================================== --- code/player/trunk/server/drivers/blobfinder/cmvision/cmvision.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/blobfinder/cmvision/cmvision.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -32,6 +32,8 @@ =========================================================================*/ #include "cmvision.h" +#include <string.h> +#include <strings.h> //==== Utility Functions ===========================================// // These could be coded as macros, but the inline versions seem to Modified: code/player/trunk/server/drivers/gps/garminnmea.cc =================================================================== --- code/player/trunk/server/drivers/gps/garminnmea.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/gps/garminnmea.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -224,7 +224,7 @@ int ParseGPRMC(const char *buf); int ParsePGRME(const char *buf); int ParseGPGST(const char *buf); - char* GetNextField(char* field, size_t len, const char* ptr); + const char* GetNextField(char* field, size_t len, const char* ptr); // utility functions to convert geodetic to UTM position void UTM(double lat, double lon, double *x, double *y); @@ -380,11 +380,13 @@ cfsetispeed(&term, B115200); cfsetospeed(&term, B115200); } +#ifdef B230400 else if (gps_baud == 230400) { cfsetispeed(&term, B230400); cfsetospeed(&term, B230400); } +#endif else { cfsetispeed(&term, B4800); @@ -615,7 +617,7 @@ //printf("reading sentence\n"); //fflush(stdout); - while(!(ptr = strchr((const char*)nmea_buf, NMEA_START_CHAR))) + while(!(ptr = strchr(nmea_buf, NMEA_START_CHAR))) { nmea_buf_len=0; memset(nmea_buf,0,sizeof(nmea_buf)); @@ -629,7 +631,7 @@ //printf("found start char:[%s]:[%d]\n", nmea_buf,nmea_buf_len); //fflush(stdout); - while(!(ptr = strchr((const char*)nmea_buf, NMEA_END_CHAR))) + while(!(ptr = strchr(nmea_buf, NMEA_END_CHAR))) { if(nmea_buf_len >= sizeof(nmea_buf) - 1) { @@ -674,7 +676,7 @@ // verify the checksum, if present. two hex digits are the XOR of all the // characters between the $ and *. - if((ptr2 = strchr((const char*)buf,NMEA_CHKSUM_CHAR)) && (strlen(ptr2) == 3)) + if((ptr2 = strchr(buf,NMEA_CHKSUM_CHAR)) && (strlen(ptr2) == 3)) { ////printf("ptr2 %s\n", ptr2); ////fflush(stdout); @@ -796,11 +798,11 @@ /* * Get the next field from an NMEA sentence. */ -char* +const char* GarminNMEA::GetNextField(char* field, size_t len, const char* ptr) { - char* start; - char* end; + const char* start; + const char* end; size_t fieldlen; if(strlen(ptr) < 2 || !(start = strchr(ptr, ','))) Modified: code/player/trunk/server/drivers/imu/MTComm.cpp =================================================================== --- code/player/trunk/server/drivers/imu/MTComm.cpp 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/imu/MTComm.cpp 2008-06-17 02:57:46 UTC (rev 6612) @@ -112,6 +112,14 @@ #define new DEBUG_NEW #endif +#ifndef CRTSCTS +#ifdef IHFLOW +#ifdef OHFLOW +#define CRTSCTS ((IHFLOW) | (OHFLOW)) +#endif +#endif +#endif + ////////////////////////////////////////////////////////////////////// // Construction/Destruction ////////////////////////////////////////////////////////////////////// Modified: code/player/trunk/server/drivers/laser/RS4LeuzeLaserDriver.cc =================================================================== --- code/player/trunk/server/drivers/laser/RS4LeuzeLaserDriver.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/RS4LeuzeLaserDriver.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -135,11 +135,7 @@ #include <math.h> #include <termios.h> -#include <vector> - #include <time.h> -#include <iostream> -#include <fstream> #include "RS4Leuze_laser.h" @@ -185,7 +181,7 @@ //bool UseSerial; int BaudRate; - char * Port; + const char * Port; bool invert; int ScanPoints; struct timeval tv;/**<termios variable time interval*/ @@ -227,7 +223,7 @@ // serial configuration - cout << "myLaser RS4 Leuze:"<< endl; + PLAYER_MSG1(1, "%s", "myLaser RS4 Leuze:"); int b = cf->ReadInt(section, "baud", 57600); switch(b) @@ -256,10 +252,10 @@ b = 57600; break; } - cout << "baud rate : " << b << endl; + PLAYER_MSG1(1, "baud rate: %d", b); - Port = strdup(cf->ReadString(section, "port", "/dev/ttyS1")); - cout << "port :" << Port << endl; + Port = cf->ReadString(section, "port", "/dev/ttyS1"); + PLAYER_MSG1(1, "port: %s", Port); // Scan points configuration int sc = cf->ReadInt(section, "scan_points", 132); @@ -287,7 +283,7 @@ Conf.resolution = DTOR(4*0.36); break; } - cout << "scan points : " << ScanPoints << endl; + PLAYER_MSG1(1, "scan points: %d", ScanPoints); //invert data from teh leuze. Check if the leuze is upside-down.Normally dat must be inverted //int sc = cf->ReadInt(section, "scan_points", 132); @@ -318,7 +314,7 @@ // this->SetError(1); // return -1; //} - cout << "S4LeuzeLaserDriver::Setup" << endl; + PLAYER_MSG1(1, "%s", "S4LeuzeLaserDriver::Setup"); // Start the device thread; spawns a new thread and executes // ExampleDriver::Main(), which contains the main loop for the driver. @@ -369,12 +365,12 @@ // Main function for device thread void RS4LeuzeLaserDriver::Main() { - cout << "RS4LeuzeLaserDriver::Main" << endl; + PLAYER_MSG1(1, "%s", "RS4LeuzeLaserDriver::Main"); bool laser_ON=1; //int i; - cout<<"Laser Ok"<<endl; + PLAYER_MSG1(1, "%s", "Laser Ok"); // The main loop; interact with the device here for(int veces = 0;;veces++) { @@ -396,7 +392,7 @@ int top_ii = Data.ranges_count; float tmp; - cout << "Data: "; + PLAYER_MSG1(1, "%s", "Data: "); for (unsigned int i = 0; i < Data.ranges_count; ++i) { tmp = myLaser->scanData.Reading[i]; @@ -411,9 +407,8 @@ //Laser upside-down Data.ranges[i] = tmp; } - cout << Data.ranges[i] << " "; + PLAYER_MSG1(1, "%.4f ", Data.ranges[i]); } - cout << endl; Publish(device_addr, PLAYER_MSGTYPE_DATA, PLAYER_LASER_DATA_SCAN, Modified: code/player/trunk/server/drivers/laser/RS4Leuze_laser.cc =================================================================== --- code/player/trunk/server/drivers/laser/RS4Leuze_laser.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/RS4Leuze_laser.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -7,7 +7,9 @@ //include #include "RS4Leuze_laser.h" +#include <unistd.h> #include <string.h> +#include <libplayercore/playercore.h> /** Default constructor. */ @@ -34,12 +36,12 @@ close(serialFD); } -void Claser::openSerial(bool *laser_ON, int Baud_rate, char * Port) +void Claser::openSerial(bool *laser_ON, int Baud_rate, const char * Port) { serialFD = open(Port, O_RDWR|O_NOCTTY); if (serialFD<0) { - cout << "Claser, Error opening serial port " << endl; + PLAYER_ERROR("Claser, Error opening serial port"); *laser_ON=0; return; } @@ -55,7 +57,7 @@ // Set configuration immediately. if (tcsetattr(serialFD, TCSANOW, &ttyset)<0) { - cout << "Claser, Error opening serial port " << endl; + PLAYER_ERROR("Claser, Error opening serial port"); *laser_ON=0; return; } @@ -118,7 +120,7 @@ if(byte != 0x00) { //cout << " Claser::scanRead(STEP 1), Error reading Laser message header" << endl; - cout << "Error reading Laser message header" << endl; + PLAYER_ERROR("Error reading Laser message header"); return 1; } } @@ -154,7 +156,7 @@ if (byte != 0xFE) { //cout << "Claser::scanRead(STEP 2), Error reading Laser message header" << endl; - cout << "Error reading Laser message header" << endl; + PLAYER_ERROR("Error reading Laser message header"); return 1; } } @@ -212,7 +214,7 @@ } else { - cout<<"Laser disconnected!!!!!!!!!!!!!!!!"<<endl; + PLAYER_ERROR("Laser disconnected!!!!!!!!!!!!!!!!"); } } Modified: code/player/trunk/server/drivers/laser/RS4Leuze_laser.h =================================================================== --- code/player/trunk/server/drivers/laser/RS4Leuze_laser.h 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/RS4Leuze_laser.h 2008-06-17 02:57:46 UTC (rev 6612) @@ -15,8 +15,6 @@ #include <time.h> #include <sys/time.h> #include <stdlib.h> -#include <iostream> -#include <fstream> using namespace std; @@ -51,9 +49,6 @@ struct timeval tv;/**<termios variable time interval*/ timeval timeStamp; /**<Time in microseconds resolution*/ - - ofstream laserDataFile; /**<Laser Scanner Data file*/ - public: //Claser(ClogMsg *lgMsg, bool *laser_ON, char dir_name[80]); /**<Opens serial port*/ @@ -67,7 +62,7 @@ int scanRead(); /**<reads one scan and puts it in scanData array*/ void runLaser(); /**<Return the scan reading from the laser*/ void closeSerial(); /**<Closes serial Port */ - void openSerial(bool *laser_ON,int Baud_rate, char * Port); /**<Opens serial Port and get the default paarameters or those given in the .cfg file*/ + void openSerial(bool *laser_ON,int Baud_rate, const char * Port); /**<Opens serial Port and get the default paarameters or those given in the .cfg file*/ RS4Leuze_laser_readings_t scanData; }; Modified: code/player/trunk/server/drivers/laser/bumper2laser.cc =================================================================== --- code/player/trunk/server/drivers/laser/bumper2laser.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/bumper2laser.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -71,17 +71,14 @@ /** @} */ -#include <iostream> -#include <cassert> -#include <cstddef> -#include <cstring> -#include <ctime> -#include <cmath> +#include <assert.h> +#include <stddef.h> +#include <string.h> +#include <time.h> +#include <math.h> #include <pthread.h> #include <libplayercore/playercore.h> -using namespace std; - extern PlayerTime * GlobalTime; #ifndef M_PI Modified: code/player/trunk/server/drivers/laser/pbs_driver.cc =================================================================== --- code/player/trunk/server/drivers/laser/pbs_driver.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/pbs_driver.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -80,8 +80,6 @@ #include <stdlib.h> #include <termios.h> #include <unistd.h> -#include <iostream> -#include <fstream> #include <string.h> #include <sys/types.h> Modified: code/player/trunk/server/drivers/laser/sicklms200.cc =================================================================== --- code/player/trunk/server/drivers/laser/sicklms200.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/sicklms200.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -456,9 +456,11 @@ case 115200: this->serial_high_speed_baudremap = B115200; break; +#ifdef B230400 case 230400: this->serial_high_speed_baudremap = B230400; break; +#endif default: printf("Unknown baud rate [%d] defaulting to B38400\n", this->serial_high_speed_baudremap); this->serial_high_speed_baudremap = B38400; Modified: code/player/trunk/server/drivers/laser/urglaserdriver.cc =================================================================== --- code/player/trunk/server/drivers/laser/urglaserdriver.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/laser/urglaserdriver.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -103,7 +103,6 @@ #include <termios.h> #include <replace/replace.h> -#include <vector> using namespace std; #include "urg_laser.h" Modified: code/player/trunk/server/drivers/localization/fakelocalize.cc =================================================================== --- code/player/trunk/server/drivers/localization/fakelocalize.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/localization/fakelocalize.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -90,11 +90,11 @@ /** @} */ #include <unistd.h> -#include <cstddef> -#include <cstdlib> -#include <ctime> -#include <cassert> -#include <cstring> +#include <stddef.h> +#include <stdlib.h> +#include <time.h> +#include <assert.h> +#include <string.h> #include <libplayercore/playercore.h> Modified: code/player/trunk/server/drivers/map/mapcspace.cc =================================================================== --- code/player/trunk/server/drivers/map/mapcspace.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/map/mapcspace.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -198,7 +198,7 @@ for(di = -r; di <= r; di++) { // stay within the radius - if((int)rint(sqrt(di*di + dj*dj)) > r) + if((int)rint(sqrt(static_cast<double>(di*di + dj*dj))) > r) continue; // make sure we stay on the map Modified: code/player/trunk/server/drivers/mixed/p2os/p2os.cc =================================================================== --- code/player/trunk/server/drivers/mixed/p2os/p2os.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/mixed/p2os/p2os.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -309,12 +309,17 @@ #include "config.h" #endif +#include "p2os.h" +#include <libplayerxdr/playerxdr.h> + #include <fcntl.h> #include <signal.h> #include <sys/stat.h> #include <sys/types.h> +#include <stddef.h> #include <stdio.h> #include <string.h> +#include <strings.h> #include <unistd.h> #include <math.h> #include <stdlib.h> /* for abs() */ @@ -324,9 +329,6 @@ #include <netinet/tcp.h> #include <netdb.h> -#include "p2os.h" -#include <libplayerxdr/playerxdr.h> - Driver* P2OS_Init(ConfigFile* cf, int section) { @@ -1614,7 +1616,6 @@ P2OS::SendReceive(P2OSPacket* pkt, bool publish_data) { P2OSPacket packet; - //double msgTime; // zero the combined data buffer. it will be filled with the latest data // by corresponding SIP::Fill*() Modified: code/player/trunk/server/drivers/mixed/rflex/rflex-io.cc =================================================================== --- code/player/trunk/server/drivers/mixed/rflex/rflex-io.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/mixed/rflex/rflex-io.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -12,7 +12,6 @@ #include <unistd.h> #include <termios.h> #include <fcntl.h> -#include <sys/signal.h> #include <sys/types.h> #include <sys/time.h> #include <sys/ioctl.h> @@ -21,6 +20,14 @@ #include "rflex-info.h" #include "rflex-io.h" +#ifndef CRTSCTS +#ifdef IHFLOW +#ifdef OHFLOW +#define CRTSCTS ((IHFLOW) | (OHFLOW)) +#endif +#endif +#endif + int iParity( enum PARITY_TYPE par ) { @@ -132,9 +139,11 @@ case 115200: return(B115200); break; +#ifdef B230400 case 230400: return(B230400); break; +#endif #ifdef B460800 // POSIX doesn't have this one #warning Including support for baud rate B460800 which is not available in all implementations of termios. Modified: code/player/trunk/server/drivers/planner/wavefront/plan_plan.c =================================================================== --- code/player/trunk/server/drivers/planner/wavefront/plan_plan.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/planner/wavefront/plan_plan.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -195,6 +195,7 @@ while (1) { + float * p; cell = plan_pop(plan); if (cell == NULL) break; @@ -204,7 +205,7 @@ //printf("pop %d %d %f\n", cell->ci, cell->cj, cell->plan_cost); - float* p = plan->dist_kernel_3x3; + p = plan->dist_kernel_3x3; for (dj = -1; dj <= +1; dj++) { ncell = plan->cells + PLAN_INDEX(plan,oi-1,oj+dj); Modified: code/player/trunk/server/drivers/position/ascension/flockofbirds.cc =================================================================== --- code/player/trunk/server/drivers/position/ascension/flockofbirds.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/position/ascension/flockofbirds.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -60,6 +60,8 @@ */ /** @} */ +#include <libplayercore/playercore.h> + #include <sys/types.h> #include <sys/stat.h> #include <sys/time.h> @@ -74,8 +76,6 @@ #include <pthread.h> #include <math.h> -#include <libplayercore/playercore.h> - // Flock of Birds Serial device interface... // two classes, the first to do the access, the second to interface with player // fairly light weight, Modified: code/player/trunk/server/drivers/position/nav200/nav200.h =================================================================== --- code/player/trunk/server/drivers/position/nav200/nav200.h 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/position/nav200/nav200.h 2008-06-17 02:57:46 UTC (rev 6612) @@ -9,6 +9,7 @@ #ifndef _NAV200_H #define _NAV200_H +#include <libplayercore/playercore.h> #include <sys/types.h> #include <sys/stat.h> #include <sys/time.h> @@ -22,7 +23,6 @@ #include <string.h> #include <pthread.h> #include <math.h> -#include <libplayercore/playercore.h> //#include <stdint.h> Modified: code/player/trunk/server/drivers/position/roboteq/roboteq.cc =================================================================== --- code/player/trunk/server/drivers/position/roboteq/roboteq.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/position/roboteq/roboteq.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -104,7 +104,6 @@ #include <string.h> // for strncpy(3),memcpy(3) #include <stdlib.h> // for atexit(3),atoi(3) #include <pthread.h> // for pthread stuff -#include <sys/poll.h> // for poll and poll_fd #include <math.h> #include <libplayercore/playercore.h> @@ -115,6 +114,14 @@ #define ROBOTEQ_CON_TIMEOUT 10 // seconds to time-out on setting RS-232 mode #define ROBOTEQ_DEFAULT_BAUD 9600 +#ifndef CRTSCTS +#ifdef IHFLOW +#ifdef OHFLOW +#define CRTSCTS ((IHFLOW) | (OHFLOW)) +#endif +#endif +#endif + // ************************************* // some assumptions made by this driver: @@ -287,7 +294,7 @@ } // check response from RoboteQ - bzero(serialin_buff, SERIAL_BUFF_SIZE); + memset(serialin_buff, 0, SERIAL_BUFF_SIZE); ret = read(roboteq_fd, serialin_buff, SERIAL_BUFF_SIZE); int beg_time = time(NULL); bool mode_changed = true; @@ -296,7 +303,7 @@ mode_changed = false; break; } - bzero(serialin_buff, SERIAL_BUFF_SIZE); + memset(serialin_buff, 0, SERIAL_BUFF_SIZE); ret = read(roboteq_fd, serialin_buff, SERIAL_BUFF_SIZE); } if (!mode_changed) @@ -331,7 +338,7 @@ usleep(25000); // check response from RoboteQ - bzero(serialin_buff, SERIAL_BUFF_SIZE); + memset(serialin_buff, 0, SERIAL_BUFF_SIZE); ret = read(roboteq_fd, serialin_buff, SERIAL_BUFF_SIZE); int beg_time = time(NULL); while (! strchr(serialin_buff, 'W')){ @@ -345,7 +352,7 @@ // failing or is the test bad? return 0; } - bzero(serialin_buff, SERIAL_BUFF_SIZE); + memset(serialin_buff, 0, SERIAL_BUFF_SIZE); ret = read(roboteq_fd, serialin_buff, SERIAL_BUFF_SIZE); } fputs("Unable to reset Roboteq to RC mode!", stderr); Modified: code/player/trunk/server/drivers/ptz/canonvcc4.cc =================================================================== --- code/player/trunk/server/drivers/ptz/canonvcc4.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/ptz/canonvcc4.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -18,6 +18,14 @@ #include <libplayercore/playercore.h> #include <replace/replace.h> +#ifndef CRTSCTS +#ifdef IHFLOW +#ifdef OHFLOW +#define CRTSCTS ((IHFLOW) | (OHFLOW)) +#endif +#endif +#endif + #define CAM_ERROR_NONE 0x30 #define CAM_ERROR_BUSY 0x31 #define CAM_ERROR_PARAM 0x35 Modified: code/player/trunk/server/drivers/ptz/ptu46.cc =================================================================== --- code/player/trunk/server/drivers/ptz/ptu46.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/ptz/ptu46.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -79,6 +79,9 @@ * set up of a player driver */ +// Includes needed for player +#include <libplayercore/playercore.h> + // serial includes #include <sys/types.h> #include <sys/stat.h> @@ -106,9 +109,6 @@ #define PTU46_VELOCITY 'v' #define PTU46_POSITION 'i' -// Includes needed for player -#include <libplayercore/playercore.h> - #define DEFAULT_PTZ_PORT "/dev/ttyR1" #define PTZ_SLEEP_TIME_USEC 100000 Modified: code/player/trunk/server/drivers/rfid/insideM300.cc =================================================================== --- code/player/trunk/server/drivers/rfid/insideM300.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/rfid/insideM300.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -89,6 +89,8 @@ #include <termios.h> #include <unistd.h> #include <sys/ioctl.h> +#include <stddef.h> +#include <stdlib.h> // Includes needed for player #include <libplayercore/playercore.h> Modified: code/player/trunk/server/drivers/rfid/rfi341_protocol.cc =================================================================== --- code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -6,9 +6,13 @@ */ #include <termios.h> #include <iostream> +#include <unistd.h> #include <fcntl.h> #include <libplayercore/playercore.h> #include <libplayercore/playercommon.h> +#include <stddef.h> +#include <stdlib.h> +#include <string.h> #include "rfi341_protocol.h" @@ -265,7 +269,7 @@ int rfi341_protocol::ReadResult () { - bzero (buffer, 256); + memset(buffer, 0, 256); // Read ACK int n = read (fd, buffer, 1); if (verbose && ((n < 0) || (buffer[0] != ACK))) Modified: code/player/trunk/server/drivers/shell/readlog.cc =================================================================== --- code/player/trunk/server/drivers/shell/readlog.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/shell/readlog.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -130,6 +130,9 @@ #include <config.h> +#include <libplayercore/playercore.h> +#include <libplayerxdr/playerxdr.h> + #include <assert.h> #include <ctype.h> #include <errno.h> @@ -137,6 +140,7 @@ #include <sys/time.h> #include <stdlib.h> #include <string.h> +#include <strings.h> #include <math.h> #include <unistd.h> @@ -144,9 +148,6 @@ #include <zlib.h> #endif -#include <libplayercore/playercore.h> -#include <libplayerxdr/playerxdr.h> - #include "encode.h" #include "readlog_time.h" Modified: code/player/trunk/server/drivers/wifi/aodv.cc =================================================================== --- code/player/trunk/server/drivers/wifi/aodv.cc 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/server/drivers/wifi/aodv.cc 2008-06-17 02:57:46 UTC (rev 6612) @@ -71,6 +71,8 @@ #include <errno.h> #include <stdio.h> #include <string.h> +#include <stddef.h> +#include <stdlib.h> #include <netinet/in.h> #include <libplayercore/playercore.h> Modified: code/player/trunk/utils/logsplitter/logsplitter.c =================================================================== --- code/player/trunk/utils/logsplitter/logsplitter.c 2008-06-17 02:43:27 UTC (rev 6611) +++ code/player/trunk/utils/logsplitter/logsplitter.c 2008-06-17 02:57:46 UTC (rev 6612) @@ -41,6 +41,10 @@ char data[1024]; char fileName[80]; double t1; + FILE *output; + FILE *rest; + struct stat fbuf; + long lastdatalen; // Save current position in file long currentPos = ftell (input); @@ -59,16 +63,14 @@ } } memset (data, 0, 1024); - + sprintf (fileName, "%lf-split.log", t1); - + // Seek to the beginning of the file fseek (input, 0L, SEEK_SET); - + // Create output file - FILE *output; - struct stat fbuf; - + if (stat (fileName, &fbuf) != 0) { output = fopen (fileName, "w+"); @@ -100,9 +102,8 @@ sprintf (fileName, "%lf-split.log", t2); if (stat (fileName, &fbuf) != 0) { - FILE *rest = fopen (fileName, "w+"); - printf ("I: Creating... %s\n", fileName); - long lastdatalen; + rest = fopen (fileName, "w+"); + printf ("I: Creating... %s\n", fileName); while (1) { fgets (data, 1024, input); @@ -137,6 +138,9 @@ long before, after; char btime[26]; const char *base_filename; + float min_timedifference; + struct stat fbuf; + struct stat ftempbuf; // We need 2 parameters if (argc != 3) @@ -148,7 +152,7 @@ } // Get the minimum time difference between two consecutive timestamps - float min_timedifference = atof (argv[1]); + min_timedifference = atof (argv[1]); base_filename = argv[2]; printf ("I: Minimum time difference is: %f seconds.\n", min_timedifference); @@ -162,8 +166,7 @@ } else printf ("I: Opening %s ...[success]\n", base_filename); - - struct stat fbuf; + stat (base_filename, &fbuf); // Create a temporary file @@ -186,7 +189,6 @@ // Close the original logfile fclose (fd); - struct stat ftempbuf; fstat (fileno (tempfd), &ftempbuf); if ((fbuf.st_size - ftempbuf.st_size) != 0) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |