From: <gb...@us...> - 2008-06-15 18:53:38
|
Revision: 6580 http://playerstage.svn.sourceforge.net/playerstage/?rev=6580&view=rev Author: gbiggs Date: 2008-06-15 18:53:44 -0700 (Sun, 15 Jun 2008) Log Message: ----------- Merging change 6578 from 2.1 branch Modified Paths: -------------- code/player/trunk/cmake/internal/SearchForStuff.cmake code/player/trunk/libplayercore/message.cc code/player/trunk/playerconfig.h.in code/player/trunk/replace/replace.h Added Paths: ----------- code/player/trunk/replace/clock_gettime.c Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake =================================================================== --- code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-06-16 00:54:14 UTC (rev 6579) +++ code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-06-16 01:53:44 UTC (rev 6580) @@ -16,7 +16,6 @@ CHECK_FUNCTION_EXISTS (round HAVE_ROUND) CHECK_INCLUDE_FILES (stdint.h HAVE_STDINT_H) CHECK_INCLUDE_FILES (strings.h HAVE_STRINGS_H) -CHECK_FUNCTION_EXISTS (compressBound NEED_COMPRESSBOUND) CHECK_INCLUDE_FILES (dns_sd.h HAVE_DNS_SD) IF (HAVE_DNS_SD) CHECK_LIBRARY_EXISTS (dns_sd DNSServiceRefDeallocate "" HAVE_DNS_SD) @@ -27,6 +26,11 @@ IF (HAVE_LIBJPEG AND HAVE_JPEGLIB_H) SET (HAVE_JPEG TRUE) ENDIF (HAVE_LIBJPEG AND HAVE_JPEGLIB_H) +SET (CMAKE_REQUIRED_INCLUDES zlib.h) +SET (CMAKE_REQUIRED_LIBRARIES z) +CHECK_FUNCTION_EXISTS (compressBound HAVE_COMPRESSBOUND) +SET (CMAKE_REQUIRED_INCLUDES) +SET (CMAKE_REQUIRED_LIBRARIES) CHECK_LIBRARY_EXISTS (z compress2 "" HAVE_LIBZ) CHECK_INCLUDE_FILES (zlib.h HAVE_ZLIB_H) @@ -34,6 +38,14 @@ SET (HAVE_Z TRUE) ENDIF (HAVE_LIBZ AND HAVE_ZLIB_H) +CHECK_LIBRARY_EXISTS (rt clock_gettime "" HAVE_LIBRT) +SET (CMAKE_REQUIRED_LIBRARIES rt) +CHECK_FUNCTION_EXISTS (clock_gettime HAVE_CLOCK_GETTIME_FUNC) +SET (CMAKE_REQUIRED_LIBRARIES) +IF (HAVE_LIBRT AND HAVE_CLOCK_GETTIME_FUNC) + SET (HAVE_CLOCK_GETTIME TRUE) +ENDIF (HAVE_LIBRT AND HAVE_CLOCK_GETTIME_FUNC) + # Endianess check INCLUDE (TestBigEndian) TEST_BIG_ENDIAN (WORDS_BIGENDIAN) Modified: code/player/trunk/libplayercore/message.cc =================================================================== --- code/player/trunk/libplayercore/message.cc 2008-06-16 00:54:14 UTC (rev 6579) +++ code/player/trunk/libplayercore/message.cc 2008-06-16 01:53:44 UTC (rev 6580) @@ -55,6 +55,7 @@ #include <libplayercore/error.h> #include <libplayercore/interface_util.h> #include <playerxdr.h> +#include <replace/replace.h> Message::Message(const struct player_msghdr & aHeader, void * data, Modified: code/player/trunk/playerconfig.h.in =================================================================== --- code/player/trunk/playerconfig.h.in 2008-06-16 00:54:14 UTC (rev 6579) +++ code/player/trunk/playerconfig.h.in 2008-06-16 01:53:44 UTC (rev 6580) @@ -6,8 +6,9 @@ #cmakedefine HAVE_POLL 1 #cmakedefine HAVE_ROUND 1 #cmakedefine HAVE_STDINT_H 1 -#cmakedefine NEED_COMPRESSBOUND 1 +#cmakedefine HAVE_COMPRESSBOUND 1 #cmakedefine INCLUDE_RTKGUI 1 +#cmakedefine HAVE_CLOCK_GETTIME 1 #ifdef HAVE_STDINT_H #include <stdint.h> Copied: code/player/trunk/replace/clock_gettime.c (from rev 6578, code/player/branches/release-2-1-patches/replace/clock_gettime.c) =================================================================== --- code/player/trunk/replace/clock_gettime.c (rev 0) +++ code/player/trunk/replace/clock_gettime.c 2008-06-16 01:53:44 UTC (rev 6580) @@ -0,0 +1,46 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2008 + * Brian Gerkey - Player + * Klaas Gadeyne - clock_gettime replacement function + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ + +#include <playerconfig.h> + +#if defined (HAVE_CLOCK_GETTIME) + +#include <sys/time.h> + +/* This replacement function originally written by Klass Gadeyne + for the Orocos Project */ +int clock_gettime(int clk_id /*ignored*/, struct timespec *tp) +{ + struct timeval now; + int rv = gettimeofday(&now, NULL); + if (rv != 0) + { + tp->tv_sec = 0; + tp->tv_nsec = 0; + return rv; + } + tp->tv_sec = now.tv_sec; + tp->tv_nsec = now.tv_usec * 1000; + return 0; +} + +#endif // defined (HAVE_CLOCK_GETTIME) Modified: code/player/trunk/replace/replace.h =================================================================== --- code/player/trunk/replace/replace.h 2008-06-16 00:54:14 UTC (rev 6579) +++ code/player/trunk/replace/replace.h 2008-06-16 01:53:44 UTC (rev 6580) @@ -89,10 +89,15 @@ double round (double x); #endif // !HAVE_ROUND -#if NEED_COMPRESSBOUND +#if !HAVE_COMPRESSBOUND unsigned long compressBound (unsigned long sourceLen); -#endif // NEED_COMPRESSBOUND +#endif // HAVE_COMPRESSBOUND +#if !HAVE_CLOCK_GETTIME + #define CLOCK_REALTIME 0 + int clock_gettime(int clk_id, struct timespec *tp); +#endif // !HAVE_CLOCK_GETTIME + #ifdef __cplusplus } #endif This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <ge...@us...> - 2008-06-16 14:19:45
|
Revision: 6590 http://playerstage.svn.sourceforge.net/playerstage/?rev=6590&view=rev Author: gerkey Date: 2008-06-16 14:19:54 -0700 (Mon, 16 Jun 2008) Log Message: ----------- fixed replacement of clock_gettime on OS X Modified Paths: -------------- code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/replace/clock_gettime.c Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-06-16 20:04:26 UTC (rev 6589) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-06-16 21:19:54 UTC (rev 6590) @@ -46,26 +46,44 @@ # Include from the binary dir to get player_interfaces.h and interface_table.h INCLUDE_DIRECTORIES (${CMAKE_CURRENT_BINARY_DIR}) -SET (playercore_srcs driver.cc - device.cc - drivertable.cc - devicetable.cc - configfile.cc - message.cc - wallclocktime.cc - plugins.cc - globals.cc - property.cpp) -PLAYER_ADD_LIBRARY (playercore ${playercore_srcs} ${player_interfaces_h} ${playerxdr_h}) # TODO: playerxdr should NOT be linked here; it's a bogus dependency coming # from the fact that message cloning functions are auto-generated into # playerxdr and used here. Those functions should go into a separate # library. -TARGET_LINK_LIBRARIES (playercore playerutils playererror playerxdr ltdl dl pthread rt) -PLAYER_ADD_LINK_LIB (ltdl dl pthread rt) -PLAYER_MAKE_PKGCONFIG ("playercore" "Player core library - part of the Player Project" "playererror" "" "" "-lltdl -lpthread -lrt") +SET(CORESRCS driver.cc + device.cc + drivertable.cc + devicetable.cc + configfile.cc + message.cc + wallclocktime.cc + plugins.cc + globals.cc + property.cpp) +SET(CORELIBS playerutils playererror playerxdr pthread) +SET(CORE_PC_LIBS "-lpthread") +PLAYER_ADD_LINK_LIB (pthread) +IF(HAVE_CLOCK_GETTIME) + SET(CORELIBS ${CORELIBS} rt) + SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lrt") + PLAYER_ADD_LINK_LIB (rt) +ELSE(HAVE_CLOCK_GETTIME) + SET(CORESRCS ${CORESRCS} ../replace/clock_gettime.c) +ENDIF(HAVE_CLOCK_GETTIME) +IF(HAVE_LIBLTDL) + SET(CORELIBS ${CORELIBS} ltdl dl) + SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lltdl -dl") + PLAYER_ADD_LINK_LIB (ltdl dl) +ENDIF(HAVE_LIBLTDL) +SET (playercore_srcs ${CORESRCS}) +PLAYER_ADD_LIBRARY (playercore ${playercore_srcs} ${player_interfaces_h} ${playerxdr_h}) + +TARGET_LINK_LIBRARIES(playercore ${CORELIBS}) +PLAYER_MAKE_PKGCONFIG ("playercore" "Player core library - part of the Player Project" "playererror" "" "" "${CORE_PC_LIBS}") + + SET (playererror_srcs error.c) PLAYER_ADD_LIBRARY (playererror ${playererror_srcs}) PLAYER_MAKE_PKGCONFIG ("playererror" "Player error reporting library - part of the Player Project" "" "" "" "") Modified: code/player/trunk/replace/clock_gettime.c =================================================================== --- code/player/trunk/replace/clock_gettime.c 2008-06-16 20:04:26 UTC (rev 6589) +++ code/player/trunk/replace/clock_gettime.c 2008-06-16 21:19:54 UTC (rev 6590) @@ -22,7 +22,6 @@ #include <playerconfig.h> -#if defined (HAVE_CLOCK_GETTIME) #include <sys/time.h> @@ -43,4 +42,3 @@ return 0; } -#endif // defined (HAVE_CLOCK_GETTIME) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <ge...@us...> - 2008-06-16 14:51:03
|
Revision: 6592 http://playerstage.svn.sourceforge.net/playerstage/?rev=6592&view=rev Author: gerkey Date: 2008-06-16 14:51:08 -0700 (Mon, 16 Jun 2008) Log Message: ----------- reworked replace file usage Modified Paths: -------------- code/player/trunk/CMakeLists.txt code/player/trunk/client_libs/libplayerc/CMakeLists.txt code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/libplayertcp/CMakeLists.txt code/player/trunk/server/CMakeLists.txt code/player/trunk/server/libplayerdrivers/CMakeLists.txt Removed Paths: ------------- code/player/trunk/replace/CMakeLists.txt code/player/trunk/replace/dummy.c Modified: code/player/trunk/CMakeLists.txt =================================================================== --- code/player/trunk/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -58,7 +58,6 @@ ADD_SUBDIRECTORY (libplayertcp) ADD_SUBDIRECTORY (libplayersd) ADD_SUBDIRECTORY (rtk2) - ADD_SUBDIRECTORY (replace) ADD_SUBDIRECTORY (server) ADD_SUBDIRECTORY (examples) ADD_SUBDIRECTORY (utils) Modified: code/player/trunk/client_libs/libplayerc/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -49,6 +49,9 @@ dev_vectormap.c dev_wifi.c dev_wsn.c) +IF(NOT HAVE_POLL) + SET(playercSrcs ${playercSrcs} ../../replace/poll.c) +ENDIF(NOT HAVE_POLL) APPEND_TO_CACHED_LIST (PLAYERC_EXTRA_LINK_LIBRARIES "Libs to link to with playerc" z m) PLAYER_ADD_LIBRARY (playerc ${playercSrcs}) @@ -69,4 +72,4 @@ PLAYER_INSTALL_HEADERS (playerc playerc.h) -PLAYER_MAKE_PKGCONFIG ("playerc" "Andrew Howard's Player C client library - part of the Player Project" "playerxdr playererror" "" "" "-lm") \ No newline at end of file +PLAYER_MAKE_PKGCONFIG ("playerc" "Andrew Howard's Player C client library - part of the Player Project" "playerxdr playererror" "" "" "-lm") Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -50,7 +50,7 @@ # from the fact that message cloning functions are auto-generated into # playerxdr and used here. Those functions should go into a separate # library. -SET(CORESRCS driver.cc +SET(playercore_srcs driver.cc device.cc drivertable.cc devicetable.cc @@ -69,15 +69,17 @@ SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lrt") PLAYER_ADD_LINK_LIB (rt) ELSE(HAVE_CLOCK_GETTIME) - SET(CORESRCS ${CORESRCS} ../replace/clock_gettime.c) + SET(playercore_srcs ${playercore_srcs} ../replace/clock_gettime.c) ENDIF(HAVE_CLOCK_GETTIME) IF(HAVE_LIBLTDL) SET(CORELIBS ${CORELIBS} ltdl dl) SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lltdl -dl") PLAYER_ADD_LINK_LIB (ltdl dl) ENDIF(HAVE_LIBLTDL) +IF(NOT HAVE_DIRNAME) + SET(playercore_srcs ${playercore_srcs} ../replace/dirname.c) +ENDIF(NOT HAVE_DIRNAME) -SET (playercore_srcs ${CORESRCS}) PLAYER_ADD_LIBRARY (playercore ${playercore_srcs} ${player_interfaces_h} ${playerxdr_h}) TARGET_LINK_LIBRARIES(playercore ${CORELIBS}) Modified: code/player/trunk/libplayertcp/CMakeLists.txt =================================================================== --- code/player/trunk/libplayertcp/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/libplayertcp/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -7,8 +7,14 @@ OPTION (ENABLE_TCP_NODELAY "Turn off Nagel's buffering algorithm (which may increase socket latency when used)" OFF) SET (playertcpSrcs socket_util.c playertcp.cc remote_driver.cc) + IF(NOT HAVE_POLL) + SET(playertcpSrcs ${playertcpSrcs} ../replace/poll.c) + ENDIF(NOT HAVE_POLL) + IF(NOT HAVE_COMPRESSBOUND) + SET(playertcpSrcs ${playertcpSrcs} ../replace/compressBound.c) + ENDIF(NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playertcp ${playertcpSrcs}) - TARGET_LINK_LIBRARIES (playertcp replace playercore playererror playerutils playerxdr) + TARGET_LINK_LIBRARIES (playertcp playercore playererror playerutils playerxdr) IF (HAVE_Z) TARGET_LINK_LIBRARIES (playertcp z) PLAYER_ADD_LINK_LIB (z) @@ -20,8 +26,14 @@ IF (INCLUDE_UDP) SET (playerudpSrcs playerudp.cc) + IF(NOT HAVE_POLL) + SET(playerudpSrcs ${playerudpSrcs} ../replace/poll.c) + ENDIF(NOT HAVE_POLL) + IF(NOT HAVE_COMPRESSBOUND) + SET(playerudpSrcs ${playerudpSrcs} ../replace/compressBound.c) + ENDIF(NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playerudp ${playerudpSrcs}) - TARGET_LINK_LIBRARIES (playerudp replace playercore playererror playerutils playerxdr) + TARGET_LINK_LIBRARIES (playerudp playercore playererror playerutils playerxdr) TARGET_LINK_LIBRARIES (playerudp z) PLAYER_MAKE_PKGCONFIG ("playerudp" "Player UDP messaging library - part of the Player Project" "playererror playercore" "" "" "") Deleted: code/player/trunk/replace/CMakeLists.txt =================================================================== --- code/player/trunk/replace/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/replace/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -1,4 +0,0 @@ -SET (replaceSrcs dummy.c) -# SET (replaceSrcs dirname.c poll.c replace.h cfmakeraw.c round.c compressBound.c) - -ADD_LIBRARY (replace STATIC ${replaceSrcs}) \ No newline at end of file Deleted: code/player/trunk/replace/dummy.c =================================================================== --- code/player/trunk/replace/dummy.c 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/replace/dummy.c 2008-06-16 21:51:08 UTC (rev 6592) @@ -1,7 +0,0 @@ -/* a dummy function so that libreplace.a is never empty, even when nothing - * needs to be replaced */ -static int player_dummy(void) -{ - return(0); -} - Modified: code/player/trunk/server/CMakeLists.txt =================================================================== --- code/player/trunk/server/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/server/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -17,7 +17,7 @@ SET (playerSrcs server.cc) # Server executable ADD_EXECUTABLE (player ${playerSrcs}) -TARGET_LINK_LIBRARIES (player playerdrivers playercore playererror playerutils playertcp playerudp playerxdr replace ${PLAYER_EXTRA_LINK_LIBRARIES}) +TARGET_LINK_LIBRARIES (player playerdrivers playercore playererror playerutils playertcp playerudp playerxdr ${PLAYER_EXTRA_LINK_LIBRARIES}) IF (INCLUDE_RTKGUI) TARGET_LINK_LIBRARIES (player rtk) ENDIF (INCLUDE_RTKGUI) Modified: code/player/trunk/server/libplayerdrivers/CMakeLists.txt =================================================================== --- code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-06-16 21:20:10 UTC (rev 6591) +++ code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-06-16 21:51:08 UTC (rev 6592) @@ -37,6 +37,13 @@ LIST (APPEND allSourceNames ${PLAYER_BUILT_DRIVEREXTRAS}) ENDIF (PLAYER_BUILT_DRIVEREXTRAS) MAP_TO_LIST (driversSrcs "${allSourceNames}" PLAYER_DRIVERSLIB_SOURCES_MAP) +IF(NOT HAVE_CFMAKERAW) + LIST(APPEND driversSrcs ../../replace/cfmakeraw.c) +ENDIF(NOT HAVE_CFMAKERAW) +IF(NOT HAVE_ROUND) + LIST(APPEND driversSrcs ../../replace/round.c) +ENDIF(NOT HAVE_ROUND) + FILTER_DUPLICATES (driversSrcs "${driversSrcs}") # MESSAGE (STATUS "Sources is ${driversSrcs}") @@ -86,4 +93,4 @@ # Package config file for libplayerdrivers PLAYER_MAKE_PKGCONFIG ("playerdrivers" "Player driver library - part of the Player Project" "playercore" "" "" "-lpthread") -PLAYER_INSTALL_HEADERS (playerdrivers driverregistry.h) \ No newline at end of file +PLAYER_INSTALL_HEADERS (playerdrivers driverregistry.h) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <th...@us...> - 2008-06-16 17:13:40
|
Revision: 6597 http://playerstage.svn.sourceforge.net/playerstage/?rev=6597&view=rev Author: thjc Date: 2008-06-16 17:13:43 -0700 (Mon, 16 Jun 2008) Log Message: ----------- merged 6499 from 2-1, lots of warnings fixed for gcc 4.2 Modified Paths: -------------- code/player/trunk/client_libs/libplayerc/client.c code/player/trunk/client_libs/libplayerc/playerc.h code/player/trunk/client_libs/libplayerc++/playerc++config.h.in code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c code/player/trunk/libplayercore/drivertable.cc code/player/trunk/libplayercore/drivertable.h code/player/trunk/server/drivers/blobfinder/acts/acts.cc code/player/trunk/server/drivers/camera/imageseq/imageseq.cc code/player/trunk/server/drivers/camera/uvc/UvcInterface.cc code/player/trunk/server/drivers/imu/nimu.cpp code/player/trunk/server/drivers/laser/lms400_cola.cc code/player/trunk/server/drivers/laser/lms400_cola.h code/player/trunk/server/drivers/laser/pbs_driver.cc code/player/trunk/server/drivers/laser/sicklms200.cc code/player/trunk/server/drivers/mixed/erratic/robot_params.h code/player/trunk/server/drivers/mixed/evolution/er1/er.cc code/player/trunk/server/drivers/mixed/p2os/p2os.cc code/player/trunk/server/drivers/mixed/p2os/robot_params.h code/player/trunk/server/drivers/position/nav200/sicknav200.cc code/player/trunk/server/drivers/ptz/canonvcc4.cc code/player/trunk/server/drivers/ptz/ptu46.cc code/player/trunk/server/drivers/ptz/sonyevid30.cc code/player/trunk/server/drivers/rfid/rfi341_protocol.cc code/player/trunk/server/drivers/rfid/rfi341_protocol.h code/player/trunk/server/drivers/shell/kartowriter.cc code/player/trunk/server/drivers/wifi/iwspy.cc code/player/trunk/utils/playerjoy/playerjoy.cc Modified: code/player/trunk/client_libs/libplayerc/client.c =================================================================== --- code/player/trunk/client_libs/libplayerc/client.c 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/client_libs/libplayerc/client.c 2008-06-17 00:13:43 UTC (rev 6597) @@ -84,7 +84,7 @@ char *data); int playerc_client_writepacket(playerc_client_t *client, player_msghdr_t *header, - char *data); + const char *data); void playerc_client_push(playerc_client_t *client, player_msghdr_t *header, void *data); int playerc_client_pop(playerc_client_t *client, @@ -188,7 +188,7 @@ { playerxdr_cleanup_message(client->data,header.addr.interf, header.type, header.subtype); } - + free(client->data); free(client->write_xdrdata); free(client->read_xdrdata); @@ -384,7 +384,7 @@ //set the datamode to pull playerc_client_datamode(client, PLAYER_DATAMODE_PULL); - + PLAYER_MSG4(3,"[%s] connected on [%s:%d] with sock %d\n", banner, client->host, client->port, client->sock); return 0; } @@ -515,7 +515,7 @@ if(client->mode != PLAYER_DATAMODE_PULL || client->data_requested) return(0); - ret = playerc_client_request(client, NULL, PLAYER_PLAYER_REQ_DATA, + ret = playerc_client_request(client, NULL, PLAYER_PLAYER_REQ_DATA, &req, NULL); if(ret == 0) { @@ -544,7 +544,7 @@ { int count; struct pollfd fd; - + if (client->sock < 0) { PLAYERC_WARN("no socket to peek at"); @@ -597,7 +597,7 @@ if (ret < 0) return NULL; nanosleep(&sleeptime,NULL); - } + } } @@ -627,8 +627,8 @@ if((ret = playerc_client_readpacket (client, &header, client->data)) < 0) return ret; } - - // One way or another, we got a new packet into (header,client->data), + + // One way or another, we got a new packet into (header,client->data), // so process it switch(header.type) { @@ -729,7 +729,7 @@ int playerc_client_request(playerc_client_t *client, playerc_device_t *deviceinfo, uint8_t subtype, - void *req_data, void **rep_data) + const void *req_data, void **rep_data) { double t; int peek; @@ -873,7 +873,7 @@ client->devinfo_count = rep_config->devices_count; player_device_devlist_t_free(rep_config); - + // Now get the driver info return playerc_client_get_driverinfo(client); } @@ -901,7 +901,7 @@ strncpy(client->devinfos[i].drivername, resp->driver_name, resp->driver_name_count); client->devinfos[i].drivername[resp->driver_name_count] = '\0'; - + player_device_driverinfo_t_free(resp); } @@ -949,7 +949,7 @@ { player_device_req_t req, *resp; int ret; - + req.addr.host = 0; req.addr.robot = 0; req.addr.interf = code; @@ -1143,7 +1143,7 @@ // Write a raw packet int playerc_client_writepacket(playerc_client_t *client, - player_msghdr_t *header, char *data) + player_msghdr_t *header, const char *data) { int bytes, ret, length; player_pack_fn_t packfunc; Modified: code/player/trunk/client_libs/libplayerc/playerc.h =================================================================== --- code/player/trunk/client_libs/libplayerc/playerc.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/client_libs/libplayerc/playerc.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -680,7 +680,7 @@ */ int playerc_client_request(playerc_client_t *client, struct _playerc_device_t *device, uint8_t reqtype, - void *req_data, void **rep_data); + const void *req_data, void **rep_data); /** @brief Wait for response from server (blocking). Modified: code/player/trunk/client_libs/libplayerc++/playerc++config.h.in =================================================================== --- code/player/trunk/client_libs/libplayerc++/playerc++config.h.in 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/client_libs/libplayerc++/playerc++config.h.in 2008-06-17 00:13:43 UTC (rev 6597) @@ -1,3 +1,6 @@ +#ifndef __PLAYER_CPP_CONFIG_H__ +#define __PLAYER_CPP_CONFIG_H__ + #cmakedefine HAVE_BOOST_THREAD #cmakedefine HAVE_BOOST_SIGNALS @@ -4,4 +7,6 @@ #if defined (HAVE_BOOST_THREAD) #define _POSIX_PTHREAD_SEMANTICS #define _REENTRANT +#endif + #endif \ No newline at end of file Modified: code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c =================================================================== --- code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-17 00:13:43 UTC (rev 6597) @@ -86,7 +86,7 @@ player_eginterf_req_t *rep; memset (&rep, 0, sizeof (player_eginterf_req_t)); req.value = blah; - if ((result = playerc_client_request (device->info.client, &device->info, PLAYER_EXAMPLE_REQ_EXAMPLE, &req, (void**)&rep)) < 0) + if ((result = playerc_client_request (device->info.client, &device->info, PLAYER_EXAMPLE_REQ_EXAMPLE, &req, &rep)) < 0) return result; device->value = rep->value; Modified: code/player/trunk/libplayercore/drivertable.cc =================================================================== --- code/player/trunk/libplayercore/drivertable.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/libplayercore/drivertable.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -1,9 +1,9 @@ /* * Player - One Hell of a Robot Server - * Copyright (C) 2000 + * Copyright (C) 2000 * Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard - * * + * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation; either version 2 of the License, or @@ -40,7 +40,7 @@ /* * $Id$ * - * class to keep track of available drivers. + * class to keep track of available drivers. */ #include <string.h> // for strncpy(3) @@ -74,14 +74,14 @@ // add a new driver to the table (new-style) int -DriverTable::AddDriver(char* name, DriverInitFn initfunc) +DriverTable::AddDriver(const char* name, DriverInitFn initfunc) { DriverEntry* thisentry; DriverEntry* preventry; - // don't check for preexisting driver, just overwrite the old driver. + // don't check for preexisting driver, just overwrite the old driver. // shouldn't really come up. - for(thisentry = head,preventry=NULL; thisentry; + for(thisentry = head,preventry=NULL; thisentry; preventry=thisentry, thisentry=thisentry->next) { if(!strncmp(thisentry->name, name, sizeof(thisentry->name))) @@ -107,7 +107,7 @@ // matches on the string name -DriverEntry* +DriverEntry* DriverTable::GetDriverEntry(const char* name) { DriverEntry* thisentry; @@ -124,7 +124,7 @@ } // get the ith driver name; returns NULL if there is no such driver -char* +char* DriverTable::GetDriverName(int idx) { DriverEntry* thisentry; Modified: code/player/trunk/libplayercore/drivertable.h =================================================================== --- code/player/trunk/libplayercore/drivertable.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/libplayercore/drivertable.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -1,9 +1,9 @@ /* * Player - One Hell of a Robot Server - * Copyright (C) 2000 + * Copyright (C) 2000 * Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard - * * + * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation; either version 2 of the License, or @@ -40,7 +40,7 @@ /* * $Id$ * - * class to keep track of available drivers. + * class to keep track of available drivers. */ #ifndef _DRIVERTABLE_H @@ -71,10 +71,10 @@ DriverInitFn initfunc; // the string name for the driver - char name[PLAYER_MAX_DRIVER_STRING_LEN]; + char name[PLAYER_MAX_DRIVER_STRING_LEN]; // next in list - DriverEntry* next; + DriverEntry* next; DriverEntry() { name[0]='\0'; next = NULL; } }; @@ -100,7 +100,7 @@ /// @brief Add a driver class to the table /// @param name Driver name (as it appears in the configuration file). /// @param initfunc Driver factory function. - int AddDriver(char* name, DriverInitFn initfunc); + int AddDriver(const char* name, DriverInitFn initfunc); /// @brief Lookup a driver entry by name /// @param name Driver name. Modified: code/player/trunk/server/drivers/blobfinder/acts/acts.cc =================================================================== --- code/player/trunk/server/drivers/blobfinder/acts/acts.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/blobfinder/acts/acts.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -252,7 +252,7 @@ // returns the enum representation of the given version string, or // ACTS_VERSION_UNKNOWN on failure to match. - acts_version_t version_string_to_enum(char* versionstr); + acts_version_t version_string_to_enum(const char* versionstr); // writes the string representation of the given version number into // versionstr, up to len. Modified: code/player/trunk/server/drivers/camera/imageseq/imageseq.cc =================================================================== --- code/player/trunk/server/drivers/camera/imageseq/imageseq.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/camera/imageseq/imageseq.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -237,8 +237,7 @@ this->data.width = image->width; this->data.height = image->height; this->data.compression = PLAYER_CAMERA_COMPRESS_RAW; - - if (this->data.image_count != image->imageSize || this->data.image == NULL) + if (this->data.image_count != static_cast<unsigned> (image->imageSize) || this->data.image == NULL) { this->data.image_count = image->imageSize; delete [] this->data.image; Modified: code/player/trunk/server/drivers/camera/uvc/UvcInterface.cc =================================================================== --- code/player/trunk/server/drivers/camera/uvc/UvcInterface.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/camera/uvc/UvcInterface.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -11,10 +11,11 @@ int UvcInterface::Open(void) { - int ret,i; - + int ret=0; + int i; + if(fd!=-1) Close(); - + try { fd=open(device,O_RDWR|O_NONBLOCK); @@ -26,15 +27,15 @@ ret=ioctl(fd,VIDIOC_QUERYCAP,&cap); if(ret==-1) throw "Error querying capabilities"; - + //check for video capture capability if(!cap.capabilities&V4L2_CAP_VIDEO_CAPTURE) throw "Device does not support video capture"; - - //check for streaming i/o capability (unnecessary?) + + //check for streaming i/o capability (unnecessary?) if(!cap.capabilities&V4L2_CAP_STREAMING) throw "Device does not support streaming i/o"; - + //check for read/write capability if(!cap.capabilities&V4L2_CAP_READWRITE) throw "Device does not support read/write i/o"; @@ -49,11 +50,11 @@ ret=ioctl(fd,VIDIOC_S_FMT,&fmt); if(ret==-1) printf("Unable to set format. (%d, %d)\r\n",ret,errno); - + ret=ioctl(fd,VIDIOC_G_FMT,&fmt); if(ret==-1) printf("Unable to retrieve format. (%d, %d)\r\n",ret,errno); - + //request memory buffers v4l2_requestbuffers rb; memset(&rb,0,sizeof(v4l2_requestbuffers)); @@ -63,13 +64,13 @@ ret = ioctl(fd,VIDIOC_REQBUFS,&rb); if(ret==-1) throw "Unable to allocate buffers"; - + //general-purpose buffer info struct v4l2_buffer buf; buffer[0]=0; buffer[1]=0; - + for(i=0;i<2;i++) { //query a buffer @@ -80,18 +81,18 @@ ret=ioctl(fd,VIDIOC_QUERYBUF,&buf); if(ret==-1) throw "Unable to query frame"; - + //retrieve the buffer memory location buffer[i]=(unsigned char*)mmap(0,buf.length,PROT_READ,MAP_SHARED,fd,buf.m.offset); length[i]=buf.length; - + if(buffer[i]==MAP_FAILED) { buffer[i]=0; throw "Unable to map frame"; } } - + for(i=0;i<2;i++) { memset(&buf,0,sizeof(v4l2_buffer)); @@ -107,7 +108,7 @@ ret=ioctl(fd,VIDIOC_STREAMON,&type); if(ret==-1) throw "Unable to initiate video stream"; - + int bufLength=length[0]; if(length[1]>bufLength) bufLength=length[1]; frame=new unsigned char[bufLength+dht_size]; @@ -124,14 +125,14 @@ int UvcInterface::Close(void) { int ret,i; - + if(fd==-1) return 0; - + int type=V4L2_BUF_TYPE_VIDEO_CAPTURE; ret=ioctl(fd,VIDIOC_STREAMOFF,&type); if(ret==-1) printf("Unable to terminate video stream. (%d, %d)\r\n",ret,errno); - + for(i=0;i<2;i++) { if(buffer[i]!=0) @@ -157,9 +158,9 @@ int UvcInterface::Read() { - int ret; + int ret=0; const int hdr=0xaf; - + try { pollfd pfd; @@ -169,9 +170,9 @@ { poll(&pfd,1,100); pthread_testcancel(); - + } while(pfd.revents==0); - + v4l2_buffer buf; memset(&buf,0,sizeof(v4l2_buffer)); buf.type=V4L2_BUF_TYPE_VIDEO_CAPTURE; @@ -179,7 +180,7 @@ ret=ioctl(fd,VIDIOC_DQBUF,&buf); if(ret==-1) throw "Unable to dequeue frame"; - + memcpy(frame,buffer[buf.index],hdr); memcpy(frame+hdr,dht_data,dht_size); memcpy(frame+hdr+dht_size,buffer[buf.index]+hdr,(buf.bytesused-hdr)); @@ -194,7 +195,7 @@ printf("%s. (%d, %d)\r\n",msg,ret,errno); return -1; } - return 0; + return 0; } int UvcInterface::GetWidth(void) const Modified: code/player/trunk/server/drivers/imu/nimu.cpp =================================================================== --- code/player/trunk/server/drivers/imu/nimu.cpp 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/imu/nimu.cpp 2008-06-17 00:13:43 UTC (rev 6597) @@ -17,13 +17,13 @@ int nimu::Open() { int ret; - ret = usb_find_busses(); + ret = usb_find_busses(); if (ret < 0) return ret; int NumDevices = usb_find_devices(); if (NumDevices < 0) return NumDevices; - + struct usb_bus *busses = usb_get_busses(); struct usb_bus *bus; @@ -54,12 +54,13 @@ } // configure the device for data output - ret = usb_control_msg(nimu_dev,0,0x02,0x02,0," ",0x0,1000); + char space[] = " "; + ret = usb_control_msg(nimu_dev,0,0x02,0x02,0,space,0x0,1000); if (ret < 0) { printf("Error sending control message2: %d (%s)\n",ret,usb_strerror()); return ret; - } + } } else { Modified: code/player/trunk/server/drivers/laser/lms400_cola.cc =================================================================== --- code/player/trunk/server/drivers/laser/lms400_cola.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/laser/lms400_cola.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -5,7 +5,7 @@ CVS: $Id$ */ #include <sys/socket.h> -#include <netdb.h> +#include <netdb.h> #include <libplayercore/playercore.h> #include "lms400_cola.h" @@ -29,24 +29,24 @@ { // Create a socket sockfd = socket (AF_INET, SOCK_STREAM, 0); - if (sockfd < 0) + if (sockfd < 0) return (-1); - + // Get the network host entry server = gethostbyname ((const char *)hostname); if (server == NULL) return (-1); - + // Fill in the sockaddr_in structure values bzero ((char *) &serv_addr, sizeof (serv_addr)); serv_addr.sin_family = AF_INET; serv_addr.sin_port = htons (portno); - bcopy ((char *)server->h_addr, + bcopy ((char *)server->h_addr, (char *)&serv_addr.sin_addr.s_addr, server->h_length); - + // Attempt to connect - if (connect (sockfd, (const sockaddr*)&serv_addr, sizeof (serv_addr)) < 0) + if (connect (sockfd, (const sockaddr*)&serv_addr, sizeof (serv_addr)) < 0) return (-1); return (0); @@ -69,7 +69,7 @@ char cmd[40]; sprintf (cmd, "sWN MDblex %i", onoff); SendCommand (cmd); - + if (ReadAnswer () != 0) return (-1); ExtendedRIS = onoff; @@ -80,7 +80,7 @@ // Get the current laser unit configuration and return it into Player format player_laser_config lms400_cola::GetConfiguration () -{ +{ player_laser_config_t cfg; cfg = Configuration; return cfg; @@ -94,13 +94,13 @@ char cmd[40]; sprintf (cmd, "sWN FLmean 0 %i", num_scans); SendCommand (cmd); - + if (ReadAnswer () != 0) return (-1); MeanFilterNumScans = num_scans; return (0); } - + //////////////////////////////////////////////////////////////////////////////// // Set the range filter parameters int @@ -109,7 +109,7 @@ char cmd[40]; sprintf (cmd, "sWN FLrang %+f %+f", ranges[0], ranges[1]); SendCommand (cmd); - + if (ReadAnswer () != 0) return (-1); RangeFilterBottomLimit = ranges[0]; @@ -125,7 +125,7 @@ char cmd[40]; sprintf (cmd, "sWN FLsel %+i", filter_mask); SendCommand (cmd); - + if (ReadAnswer () != 0) return (-1); FilterMask = filter_mask; @@ -137,18 +137,18 @@ unsigned char* lms400_cola::ParseIP (char* ip) { - char* tmp = (char*) malloc (strlen (ip) + 1); + char* tmp = (char*) malloc (strlen (ip) + 1); unsigned char* _ip = (unsigned char*) malloc (4); strcpy (tmp, ip); - _ip[0] = atoi (strtok (tmp, ".")); + _ip[0] = atoi (strtok (tmp, ".")); for (int i = 1; i < 4; i++) _ip[i] = atoi (strtok (NULL, ".")); free (tmp); return _ip; } - + //////////////////////////////////////////////////////////////////////////////// // Set the desired userlevel by logging in with the appropriate password int @@ -172,7 +172,7 @@ SendCommand ("sRN EImac "); if (ReadAnswer () != 0) return (-1); - + strtok ((char*) buffer, " "); strtok (NULL, " "); @@ -188,7 +188,7 @@ *macaddress = mac; return (0); } - + //////////////////////////////////////////////////////////////////////////////// // Set the IP address of the LMS400 int @@ -197,7 +197,7 @@ unsigned char* ip_str; ip_str = ParseIP (ip); char cmd[80]; - + sprintf (cmd, "sWN EIip %X %X %X %X", ip_str[0], ip_str[1], ip_str[2], ip_str[3]); free (ip_str); SendCommand (cmd); @@ -217,7 +217,7 @@ sprintf (cmd, "sWN EIgate %X %X %X %X", gw_str[0], gw_str[1], gw_str[2], gw_str[3]); free (gw_str); SendCommand (cmd); - + return (ReadAnswer ()); } @@ -255,9 +255,9 @@ int lms400_cola::ResetDevice () { - char* cmd = "sMN mDCreset "; + const char* cmd = "sMN mDCreset "; SendCommand (cmd); - + return (ReadAnswer ()); } @@ -266,9 +266,9 @@ int lms400_cola::TerminateConfiguration () { - char* cmd = "sMN Run"; + const char* cmd = "sMN Run"; SendCommand (cmd); - + return (ReadConfirmationAndAnswer ()); } @@ -279,40 +279,40 @@ float angle_start, float angle_range) { char cmd[80]; - sprintf (cmd, "sMN mSCconfigbyang 04 %s %+f 01 %+f %+f", + sprintf (cmd, "sMN mSCconfigbyang 04 %s %+f 01 %+f %+f", password, ang_res, angle_start, angle_range); SendCommand (cmd); - + return (ReadConfirmationAndAnswer ()); } //////////////////////////////////////////////////////////////////////////////// // Set the laser scanning frequency. Requires userlevel 2. Unused for now. int - lms400_cola::SetScanningFrequency (const char* password, float freq, + lms400_cola::SetScanningFrequency (const char* password, float freq, float angle_start, float angle_range) { char cmd[80]; - sprintf (cmd, "sMN mSCconfigbyfreq 04 %s %+f 01 %+f %+f", + sprintf (cmd, "sMN mSCconfigbyfreq 04 %s %+f 01 %+f %+f", password, freq, angle_start, angle_range); SendCommand (cmd); - + return (ReadConfirmationAndAnswer ()); } //////////////////////////////////////////////////////////////////////////////// // Set both resolution and frequency without going to a higher user level (?) int - lms400_cola::SetResolutionAndFrequency (float freq, float ang_res, + lms400_cola::SetResolutionAndFrequency (float freq, float ang_res, float angle_start, float angle_range) { char cmd[80]; - sprintf (cmd, "sMN mSCsetscanconfig %+.2f %+.2f %+.2f %+.2f", + sprintf (cmd, "sMN mSCsetscanconfig %+.2f %+.2f %+.2f %+.2f", freq, ang_res, angle_start, angle_range); - SendCommand (cmd); - + SendCommand (cmd); + int error = ReadConfirmationAndAnswer (); - + // If no error, parse the results if (error == 0) { @@ -320,18 +320,18 @@ int ErrorCode = strtol (strtok (NULL, " "), NULL, 16); long int sf = strtol (strtok (NULL, " "), NULL, 16); long int re = strtol (strtok (NULL, " "), NULL, 16); - + if ((ErrorCode != 0) && (verbose)) printf (">> Warning: got an error code %d\n", ErrorCode); - + memcpy (&Configuration.scanning_frequency, &sf, sizeof (uint32_t)); memcpy (&Configuration.resolution, &re, sizeof (uint32_t)); - - if (verbose) - printf (">> Measured value quality is: %ld [5-10]\n", + + if (verbose) + printf (">> Measured value quality is: %ld [5-10]\n", strtol (strtok (NULL, " "), NULL, 16)); } - + return (error); } @@ -345,9 +345,9 @@ sprintf (cmd, "sMN mLRreqdata %x", 0x20); else sprintf (cmd, "sMN mLRreqdata %x", 0x21); - + SendCommand (cmd); - + return (ReadConfirmationAndAnswer ()); } @@ -358,11 +358,11 @@ { player_laser_data_t player_data; player_data.ranges_count = -1; - + char cs_read = 0, cs_calc = 0; - int length = 0; + int length = 0; int current = 0; - + bzero (buffer, 256); if (!MeasurementQueue->empty ()) { @@ -375,7 +375,7 @@ { if (verbose == 2) printf (">>> Queue empty. Reading from socket...\n"); n = read (sockfd, buffer, 8); - if (n < 0) + if (n < 0) { if (verbose) printf (">>> E: error reading from socket!\n"); return (player_data); @@ -386,7 +386,7 @@ n = read (sockfd, buffer, 255); return (player_data); } - + // find message length length = ( (buffer[4] << 24) | (buffer[5] << 16) | (buffer[6] << 8) | (buffer[7]) ); do @@ -394,13 +394,13 @@ n = read (sockfd, &buffer[current], length-current); current += n; } while (current < length); - + // read checksum: - read (sockfd, &cs_read, 1); - + read (sockfd, &cs_read, 1); + for (int i = 0; i < length; i++) cs_calc ^= buffer[i]; - + if (cs_calc != cs_read) { if (verbose) printf (">>> E: checksums do not match!\n"); @@ -411,14 +411,14 @@ // parse measurements header and fill in the configuration parameters MeasurementHeader_t meas_header; memcpy (&meas_header, (void *)buffer, sizeof (MeasurementHeader_t)); - + Configuration.min_angle = meas_header.StartingAngle / 10000.0; Configuration.resolution = meas_header.AngularStepWidth / 10000.0; - Configuration.max_angle = + Configuration.max_angle = ((float) meas_header.NumberMeasuredValues) * Configuration.resolution + Configuration.min_angle; Configuration.scanning_frequency = meas_header.ScanningFrequency; - - if (verbose == 2) printf (">>> Reading %d values from %f to %f\n", + + if (verbose == 2) printf (">>> Reading %d values from %f to %f\n", meas_header.NumberMeasuredValues, meas_header.StartingAngle / 10000.0, ((float) meas_header.NumberMeasuredValues) * Configuration.resolution + Configuration.min_angle); @@ -437,14 +437,14 @@ player_data.id = 0; player_data.ranges = new float[ player_data.ranges_count]; player_data.intensity = new uint8_t[ player_data.intensity_count]; - - memcpy (&player_data.id, &buffer[sizeof(MeasurementHeader_t) + - meas_header.NumberMeasuredValues * 3 + + + memcpy (&player_data.id, &buffer[sizeof(MeasurementHeader_t) + + meas_header.NumberMeasuredValues * 3 + 14], 2); // Parse the read buffer and copy values into our distance/intensity buffer for (int i = 0; i < meas_header.NumberMeasuredValues ; i++) - { + { if (meas_header.Format == 0x20 || meas_header.Format == 0x21) { memcpy (&distance, (void *)&buffer[index], sizeof (uint16_t) ); @@ -455,12 +455,12 @@ memcpy (&remission, (void *)&buffer[index], sizeof (uint8_t) ); index += sizeof (uint8_t); } - player_data.ranges[i] = distance * meas_header.DistanceScaling / 1000.0; + player_data.ranges[i] = distance * meas_header.DistanceScaling / 1000.0; player_data.intensity[i] = remission * meas_header.RemissionScaling; - - if (verbose == 2) - printf (" >>> [%i] dist: %i\t remission: %i\n", i, - distance * meas_header.DistanceScaling , + + if (verbose == 2) + printf (" >>> [%i] dist: %i\t remission: %i\n", i, + distance * meas_header.DistanceScaling , remission * meas_header.RemissionScaling); } @@ -474,20 +474,20 @@ { char cmd[40]; sprintf (cmd, "sMN mLRstopdata"); - SendCommand (cmd); - + SendCommand (cmd); + return (ReadConfirmationAndAnswer ()); } //////////////////////////////////////////////////////////////////////////////// // Send a command to the laser unit. Returns -1 on error. int - lms400_cola::SendCommand (char* cmd) + lms400_cola::SendCommand (const char* cmd) { - if (verbose) + if (verbose) printf (">> Sent: \"%s\"\n", cmd); assemblecommand ((unsigned char *) cmd, strlen (cmd)); - + n = write (sockfd, command, commandlength); if (n < 0) return (-1); @@ -502,7 +502,7 @@ { bzero (buffer, 256); n = read (sockfd, buffer, 8); - if (n < 0) + if (n < 0) return (-1); if (buffer[0] != 0x02 || buffer[1] != 0x02 || buffer[2] != 0x02 || buffer[3] != 0x02) @@ -511,7 +511,7 @@ n = read (sockfd, buffer, 255); return (-1); } - + // Find message length int length = ( (buffer[4] << 24) | (buffer[5] << 16) | (buffer[6] << 8) | (buffer[7]) ); int current = 0; @@ -524,18 +524,18 @@ bufferlength = length; if ((verbose) && (buffer[0] != 0x20)) printf (">> Received: \"%s\"\n", buffer); - + // Check for error if (strncmp ((const char*)buffer, "sFA", 3) == 0) { strtok ((char*)buffer, " "); printf (">> E: Got an error message with code 0x%s\n", strtok (NULL, " ")); } - + // Read checksum: char cs_read = 0; - read (sockfd, &cs_read, 1); - + read (sockfd, &cs_read, 1); + // printf ("%d %d 0x%x\n", bufferlength, sizeof(MeasurementHeader_t), buffer[0]); if (buffer[0] == 's') return (0); @@ -585,7 +585,7 @@ { unsigned char checksum = 0; int index = 0; - + command[0] = 0x02; // Messages start with 4 STX's command[1] = 0x02; command[2] = 0x02; @@ -594,7 +594,7 @@ command[5] = (len >> 16) & 0xff; command[6] = (len >> 8) & 0xff; command[7] = (len ) & 0xff; - + for (index = 0; index < len; index++) { command[index + 8] = cmd[index]; @@ -602,7 +602,7 @@ } command[8 + len] = checksum; command[9 + len] = 0x00; - + commandlength = 9 + len; return (0); } Modified: code/player/trunk/server/drivers/laser/lms400_cola.h =================================================================== --- code/player/trunk/server/drivers/laser/lms400_cola.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/laser/lms400_cola.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -13,7 +13,7 @@ //////////////////////////////////////////////////////////////////////////////// typedef struct -{ +{ unsigned char* string; int length; } MeasurementQueueElement_t; @@ -38,7 +38,7 @@ { public: lms400_cola (const char* host, int port, int debug_mode); - + // Creates socket, connects int Connect (); int Disconnect (); @@ -47,28 +47,28 @@ int SetAngularResolution (const char* password, float ang_res, float angle_start, float angle_range); int SetScanningFrequency (const char* password, float freq, float angle_start, float angle_range); int SetResolutionAndFrequency (float freq, float ang_res, float angle_start, float angle_range); - + int StartMeasurement (bool intensity = true); player_laser_data ReadMeasurement (); int StopMeasurement (); - + int SetUserLevel (int8_t userlevel, const char* password); int GetMACAddress (char** macadress); - + int SetIP (char* ip); int SetGateway (char* gw); int SetNetmask (char* mask); int SetPort (uint16_t port); - + int ResetDevice (); int TerminateConfiguration (); - - int SendCommand (char* cmd); + + int SendCommand (const char* cmd); int ReadResult (); - // for "Variables", Commands that only reply with one Answer message + // for "Variables", Commands that only reply with one Answer message int ReadAnswer (); // for "Procedures", Commands that reply with a Confirmation message and an Answer message - int ReadConfirmationAndAnswer (); + int ReadConfirmationAndAnswer (); int EnableRIS (int onoff); player_laser_config GetConfiguration (); Modified: code/player/trunk/server/drivers/laser/pbs_driver.cc =================================================================== --- code/player/trunk/server/drivers/laser/pbs_driver.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/laser/pbs_driver.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -142,7 +142,7 @@ int encodePBS(unsigned char *uncoded, unsigned char *encoded, int length); int ConvertToM(unsigned char *pPbsDataHex, float *pPbsDataMm, int length); unsigned int combineTwoCharsToInt(unsigned char MSB, unsigned char LSB); - bool InitializeCom(char ComNumber[10]); + bool InitializeCom(const char *ComNumber); int Write_Buffer(unsigned char *chars, DWORD dwToWrite); int Read_Single_Char(unsigned char *result); @@ -1150,16 +1150,16 @@ /// Function for setting up the com port -bool PBSDriver::InitializeCom(char ComNumber[10]) +bool PBSDriver::InitializeCom(const char *Port_Name) { - char *Port_Name = ComNumber; // Serial port name. + //char *Port_Name = ComNumber; // Serial port name. ifd = open(Port_Name, O_RDWR | O_NOCTTY | O_NDELAY); if (ifd == -1) { return 0; - perror("open_port: Unable to open /dev/ttyS0 - "); + perror("open_port: Unable to open serial port"); } else { Modified: code/player/trunk/server/drivers/laser/sicklms200.cc =================================================================== --- code/player/trunk/server/drivers/laser/sicklms200.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/laser/sicklms200.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -619,7 +619,8 @@ { player_laser_config_t * config = reinterpret_cast<player_laser_config_t *> (data); - int old_scan_width, old_scan_res; + int old_scan_width = this->scan_width; + int old_scan_res = this->scan_res; this->intensity = config->intensity; this->scan_res = (int) rint(RTOD(config->resolution)*100); Modified: code/player/trunk/server/drivers/mixed/erratic/robot_params.h =================================================================== --- code/player/trunk/server/drivers/mixed/erratic/robot_params.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/mixed/erratic/robot_params.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -1,9 +1,9 @@ /** * Videre Erratic robot driver for Player - * + * * Copyright (C) 2006 * Videre Design - * Copyright (C) 2000 + * Copyright (C) 2000 * Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard * * This program is free software; you can redistribute it and/or modify @@ -34,51 +34,51 @@ typedef struct { - double AngleConvFactor; // - char* Class; - double DiffConvFactor; // - double DistConvFactor; // - int FrontBumpers; // - double GyroScaler; // - int HasMoveCommand; // - int Holonomic; // - int IRNum; // - int IRUnit; // - int LaserFlipped; // - char* LaserIgnore; - char* LaserPort; - int LaserPossessed; // - int LaserPowerControlled; // - int LaserTh; // - int LaserX; // - int LaserY; // - int MaxRVelocity; // - int MaxVelocity; // - int NewTableSensingIR; // - int NumFrontBumpers; // - int NumRearBumpers; // - double RangeConvFactor; // - int RearBumpers; // - int RequestEncoderPackets; // - int RequestIOPackets; // - int RobotDiagonal; // - int RobotLength; // - int RobotRadius; // - int RobotWidth; // - int RobotAxleOffset; // - int RotAccel; // - int RotDecel; // - int RotVelMax; // - int SettableAccsDecs; // - int SettableVelMaxes; // - char* Subclass; - int SwitchToBaudRate; // - int TableSensingIR; // - int TransAccel; // - int TransDecel; // - int TransVelMax; // - int Vel2Divisor; // - double VelConvFactor; // + double AngleConvFactor; // + const char* Class; + double DiffConvFactor; // + double DistConvFactor; // + int FrontBumpers; // + double GyroScaler; // + int HasMoveCommand; // + int Holonomic; // + int IRNum; // + int IRUnit; // + int LaserFlipped; // + const char* LaserIgnore; + const char* LaserPort; + int LaserPossessed; // + int LaserPowerControlled; // + int LaserTh; // + int LaserX; // + int LaserY; // + int MaxRVelocity; // + int MaxVelocity; // + int NewTableSensingIR; // + int NumFrontBumpers; // + int NumRearBumpers; // + double RangeConvFactor; // + int RearBumpers; // + int RequestEncoderPackets; // + int RequestIOPackets; // + int RobotDiagonal; // + int RobotLength; // + int RobotRadius; // + int RobotWidth; // + int RobotAxleOffset; // + int RotAccel; // + int RotDecel; // + int RotVelMax; // + int SettableAccsDecs; // + int SettableVelMaxes; // + const char* Subclass; + int SwitchToBaudRate; // + int TableSensingIR; // + int TransAccel; // + int TransDecel; // + int TransVelMax; // + int Vel2Divisor; // + double VelConvFactor; // int NumSonars; player_pose3d_t sonar_pose[32]; int NumIR; Modified: code/player/trunk/server/drivers/mixed/evolution/er1/er.cc =================================================================== --- code/player/trunk/server/drivers/mixed/evolution/er1/er.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/mixed/evolution/er1/er.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -973,8 +973,10 @@ float ER::BytesToFloat(unsigned char *ptr) { - uint32_t rawi = BytesToInt32 (ptr); - return *reinterpret_cast<float *>(&rawi); + float res; + int intermediate = BytesToInt32 (ptr); + memcpy(&res,&intermediate,sizeof(res)); + return res; } int Modified: code/player/trunk/server/drivers/mixed/p2os/p2os.cc =================================================================== --- code/player/trunk/server/drivers/mixed/p2os/p2os.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/mixed/p2os/p2os.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -1614,7 +1614,7 @@ P2OS::SendReceive(P2OSPacket* pkt, bool publish_data) { P2OSPacket packet; - double msgTime; + //double msgTime; // zero the combined data buffer. it will be filled with the latest data // by corresponding SIP::Fill*() @@ -3097,7 +3097,7 @@ // Followed by the carry time command[0] = GRIPPERVAL; command[2] = liftCarryVal & 0x00FF; - command[3] = liftCarryVal & 0xFF00; + command[3] = (liftCarryVal & 0xFF00) >> 8; packet.Build (command, 4); SendReceive (&packet); } Modified: code/player/trunk/server/drivers/mixed/p2os/robot_params.h =================================================================== --- code/player/trunk/server/drivers/mixed/p2os/robot_params.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/mixed/p2os/robot_params.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -85,7 +85,7 @@ typedef struct { double AngleConvFactor; // - char* Class; + const char* Class; double DiffConvFactor; // double DistConvFactor; // int FrontBumpers; // @@ -95,8 +95,8 @@ int IRNum; // int IRUnit; // int LaserFlipped; // - char* LaserIgnore; - char* LaserPort; + const char* LaserIgnore; + const char* LaserPort; int LaserPossessed; // int LaserPowerControlled; // int LaserTh; // @@ -121,7 +121,7 @@ int SettableAccsDecs; // int SettableVelMaxes; // int SonarNum; // - char* Subclass; + const char* Subclass; int SwitchToBaudRate; // int TableSensingIR; // int TransAccel; // Modified: code/player/trunk/server/drivers/position/nav200/sicknav200.cc =================================================================== --- code/player/trunk/server/drivers/position/nav200/sicknav200.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/position/nav200/sicknav200.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -472,7 +472,7 @@ return (0); } - char* layerName = "0"; // Dumb name. + char layerName[] = "0"; // Dumb name. // Request for map info if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, @@ -518,7 +518,7 @@ // Request for layer data else if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_VECTORMAP_REQ_GET_LAYER_DATA, this->vectormap_addr)) { - char* featureName = "point"; + char featureName[] = "point"; player_vectormap_feature_data feature; memset(&feature, 0, sizeof(feature)); feature.name = featureName; Modified: code/player/trunk/server/drivers/ptz/canonvcc4.cc =================================================================== --- code/player/trunk/server/drivers/ptz/canonvcc4.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/ptz/canonvcc4.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -46,7 +46,7 @@ static unsigned int error_code; -class canonvcc4:public Driver +class canonvcc4:public Driver { private: bool ptz_fd_blocking; @@ -68,7 +68,7 @@ virtual int SendAbsZoom(int zoom); virtual int GetAbsZoom(int* zoom); virtual int GetAbsPanTilt(int* pan, int* tilt); - virtual void PrintPacket(char* str, unsigned char* cmd, int len); + virtual void PrintPacket(const char* str, unsigned char* cmd, int len); public: @@ -87,7 +87,7 @@ void ProcessCommand(player_ptz_cmd_t & command); int pandemand , tiltdemand , zoomdemand ; - // MessageHandler + // MessageHandler int ProcessMessage(QueuePointer &resp_queue, player_msghdr * hdr, void * data); // int ProcessMessage(ClientData * client, player_msghdr * hdr, uint8_t * data, uint8_t * resp_data, int * resp_len); @@ -96,7 +96,7 @@ }; /************************************************************************/ -Driver* +Driver* canonvcc4_Init(ConfigFile* cf, int section) { return((Driver*)(new canonvcc4(cf, section))); @@ -105,7 +105,7 @@ /************************************************************************/ // a driver registration function -void +void canonvcc4_Register(DriverTable* table) { table->AddDriver("canonvcc4", canonvcc4_Init); @@ -113,7 +113,7 @@ /************************************************************************/ -//canonvcc4::canonvcc4(ConfigFile* cf, int section) +//canonvcc4::canonvcc4(ConfigFile* cf, int section) // : Driver(cf, section, true, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_PTZ_CODE, PLAYER_OPEN_MODE) canonvcc4::canonvcc4( ConfigFile* cf, int section) @@ -128,7 +128,7 @@ } /************************************************************************/ -int +int canonvcc4::Setup() { int pan,tilt; @@ -139,14 +139,14 @@ fflush(stdout); // open it. non-blocking at first, in case there's no ptz unit. - if((ptz_fd = + if((ptz_fd = open(ptz_serial_port, O_RDWR | O_SYNC | O_NONBLOCK, S_IRUSR | S_IWUSR )) < 0 ) { perror("canonvcc4::Setup():open():"); return(-1); - } - + } + if(tcflush(ptz_fd, TCIFLUSH ) < 0 ) { perror("canonvcc4::Setup():tcflush():"); @@ -164,14 +164,14 @@ // ptz_fd_blocking = false; err = setPower(0); - fprintf(stderr, "\nPowering off/on the camera!!!!!!!!!!!!!!\n"); - err = setPower(1); + fprintf(stderr, "\nPowering off/on the camera!!!!!!!!!!!!!!\n"); + err = setPower(1); while (error_code == CAM_ERROR_BUSY) { fprintf(stdout, "power on busy: %x\n", error_code); err = setPower(1); } - if ((err != 0) && + if ((err != 0) && (error_code != CAM_ERROR_NONE) && (error_code != CAM_ERROR_MODE)) { printf("Could not set power on: %x\n", error_code); @@ -197,7 +197,7 @@ if (err) { printf("Couldn't connect to PTZ device most likely because the camera\n" - "is not connected or is connected not to %s; %x\n", + "is not connected or is connected not to %s; %x\n", ptz_serial_port, error_code); setPower(0); close(ptz_fd); @@ -218,7 +218,7 @@ close(ptz_fd); return -1; } - + /* ok, we got data, so now set NONBLOCK, and continue */ if ((flags = fcntl(ptz_fd, F_GETFL)) < 0) { @@ -237,7 +237,7 @@ } // ptz_fd_blocking = true; puts("Done."); - + // zero the command and data buffers player_ptz_data_t data; player_ptz_cmd_t cmd; @@ -246,11 +246,11 @@ cmd.pan = cmd.tilt = cmd.zoom = 0; StartThread(); - + return(0); } /************************************************************************/ -int +int canonvcc4::configurePort() { struct termios tio; @@ -265,7 +265,7 @@ cfmakeraw(&tio); cfsetospeed(&tio, B9600); cfsetispeed(&tio, B9600); - if (tcsetattr(ptz_fd, TCSAFLUSH, &tio) < 0) + if (tcsetattr(ptz_fd, TCSAFLUSH, &tio) < 0) { fprintf(stderr, "Could not config serial port.\n"); return -1; @@ -273,21 +273,21 @@ tcgetattr(ptz_fd, &tio); /* check for hardware flow control */ - + //tio.c_cflag |= CRTSCTS; - + tio.c_cflag &= ~CRTSCTS; tcsetattr(ptz_fd, TCSAFLUSH, &tio); return 0; } /************************************************************************/ -int +int canonvcc4::Shutdown() { if(ptz_fd == -1) return(0); - + StopThread(); usleep(PTZ_SLEEP_TIME_USEC); SendAbsPanTilt(0,0); @@ -309,7 +309,7 @@ if(len > MAX_PTZ_COMMAND_LENGTH) { - fprintf(stderr, + fprintf(stderr, "CANNONvcc4::SendCommand(): message is too large (%d bytes)\n", len); return(-1); @@ -335,7 +335,7 @@ if(len > MAX_PTZ_REQUEST_LENGTH) { - fprintf(stderr, + fprintf(stderr, "canonvcc4::SendRequest(): message is too large (%d bytes)\n", len); return(-1); @@ -353,7 +353,7 @@ /************************************************************************/ void -canonvcc4::PrintPacket(char* str, unsigned char* cmd, int len) +canonvcc4::PrintPacket(const char* str, unsigned char* cmd, int len) { for(int i=0;i<len;i++) printf(" %.2x", cmd[i]); @@ -371,22 +371,22 @@ int ppan, ttilt; ppan = pan; ttilt = tilt; - if (abs(pan) > PTZ_PAN_MAX) + if (abs(pan) > PTZ_PAN_MAX) { if(pan < -PTZ_PAN_MAX) ppan = (int)-PTZ_PAN_MAX; - else + else if(pan > PTZ_PAN_MAX) ppan = (int)PTZ_PAN_MAX; //puts("Camera pan angle thresholded"); } - if (tilt > PTZ_TILT_MAX) + if (tilt > PTZ_TILT_MAX) ttilt = (int)PTZ_TILT_MAX; - else + else if(tilt < PTZ_TILT_MIN) ttilt = (int)PTZ_TILT_MIN; //puts("Camera pan angle thresholded"); - + //puts("Camera tilt angle thresholded"); convpan = (int)floor(ppan/.1125) + 0x8000; @@ -402,7 +402,7 @@ sprintf((char *)buf, "%X", convpan); - command[5] = buf[0]; + command[5] = buf[0]; command[6] = buf[1]; command[7] = buf[2]; command[8] = buf[3]; @@ -418,7 +418,7 @@ return(ReceiveCommandAnswer()); } /************************************************************************/ -int +int canonvcc4::setDefaultTiltRange() { unsigned char command[MAX_PTZ_COMMAND_LENGTH]; @@ -435,7 +435,7 @@ mintilt = (int)(floor(PTZ_TILT_MIN/.1125) + 0x8000); sprintf((char *)buf, "%X", mintilt); - command[6] = buf[0]; + command[6] = buf[0]; command[7] = buf[1]; command[8] = buf[2]; command[9] = buf[3]; @@ -452,7 +452,7 @@ SendCommand(command, 15); // PrintPacket( "setDefaultRange: ", command, 15); return(ReceiveCommandAnswer()); - + } /************************************************************************/ @@ -527,7 +527,7 @@ unsigned char buf[4]; unsigned int u_zoom; int i; - + command[0] = 0xFF; command[1] = 0x30; command[2] = 0x30; @@ -559,7 +559,7 @@ u_zoom = 0; for (i = 0; i < 4; i++) u_zoom += buf[i] * (unsigned int) pow(16.0, (double)(3 - i)); - *zoom = u_zoom; + *zoom = u_zoom; return(0); } @@ -571,11 +571,11 @@ unsigned char buf[5]; int i; - if(zoom < 0) + if(zoom < 0) zoom = 0; //puts("Camera zoom thresholded"); - - else + + else if(zoom > MAX_ZOOM) zoom = MAX_ZOOM; @@ -592,10 +592,10 @@ buf[i] = '0'; // zoom position - command[5] = buf[0]; - command[6] = buf[1]; - command[7] = buf[2]; - command[8] = buf[3]; + command[5] = buf[0]; + command[6] = buf[1]; + command[7] = buf[2]; + command[8] = buf[3]; command[9] = 0xEF; if (SendCommand(command, 10)) @@ -613,13 +613,13 @@ poll_fd.fd = ptz_fd; poll_fd.events = POLLIN; - + if (poll(&poll_fd, 1, 1000) <= 0) return -1; len = read(ptz_fd, reply, size); if (len < 0) return -1; - + return len; } @@ -655,7 +655,7 @@ for(num = 1; num <= MAX_PTZ_REQUEST_LENGTH; num++) { err = read_ptz(&byte, 1); - if (err == 0) + if (err == 0) continue; if (err < 0) { @@ -716,7 +716,7 @@ { // if we don't get any bytes, or if we've just exceeded the limit // then return null - err = read_ptz(&byte, 1); + err = read_ptz(&byte, 1); if (byte == (unsigned char)0xFE) { reply[0] = byte; @@ -732,7 +732,7 @@ err = read_ptz(&byte, 1); if (err == 0) continue; - if (err < 0) + if (err < 0) { // there are no more bytes, so check the last byte for the footer if (reply[len - 1] != (unsigned char)0xEF) @@ -757,8 +757,8 @@ fputs("Arvcc4::packetHandler: Incorrect number of bytes in response packet.", stderr); return -1; } - - if (reply[0] != (unsigned char)0xFE || + + if (reply[0] != (unsigned char)0xFE || reply[len - 1] != (unsigned char)0xEF) { fputs("canonvcc4::receiveRequestArvcc4: Bad header or footer character in response packet.", stderr); @@ -821,45 +821,45 @@ /************************************************************************/ // this function will be run in a separate thread -void +void canonvcc4::Main() { player_ptz_data_t data; int pan, tilt, zoom; - while(1) + while(1) { pthread_testcancel(); ProcessMessages(); /* get current state */ if(GetAbsPanTilt(&pan,&tilt) < 0) { - fputs("canonvcc4:Main():GetAbsPanTilt() errored. bailing.\n", + fputs("canonvcc4:Main():GetAbsPanTilt() errored. bailing.\n", stderr); pthread_exit(NULL); } /* get current state */ - + if(GetAbsZoom(&zoom) < 0) { fputs("canonvcc4:Main():GetAbsZoom() errored. bailing.\n", stderr); pthread_exit(NULL); } - + // Do the necessary coordinate conversions. Camera's natural pan // coordinates increase clockwise; we want them the other way, so // we negate pan here. Zoom values are converted from arbitrary // units to a field of view (in degrees). pan = -pan; - //zoom = this->maxfov + (zoom * (this->maxfov - this->minfov)) / 1960; + //zoom = this->maxfov + (zoom * (this->maxfov - this->minfov)) / 1960; data.pan = DTOR((unsigned short)pan); data.tilt = DTOR((unsigned short)tilt); - data.zoom = (unsigned short) (zoom - 3056)/ZOOM_CONV_FACTOR; + data.zoom = (unsigned short) (zoom - 3056)/ZOOM_CONV_FACTOR; pthread_testcancel(); - + Publish(device_addr, PLAYER_MSGTYPE_DATA, PLAYER_PTZ_DATA_STATE, &data,sizeof(player_ptz_data_t),NULL); usleep(PTZ_SLEEP_TIME_USEC); @@ -871,8 +871,8 @@ assert(hdr); assert(data); - if (Message::MatchMessage(hdr, - PLAYER_MSGTYPE_REQ, + if (Message::MatchMessage(hdr, + PLAYER_MSGTYPE_REQ, PLAYER_PTZ_REQ_GENERIC, device_addr)) { assert(hdr->size == sizeof(player_ptz_req_generic_t)); @@ -880,15 +880,15 @@ player_ptz_req_generic_t *cfg = (player_ptz_req_generic_t *)data; // check whether command or inquiry... - if (cfg->config[0] == 0x01) + if (cfg->config[0] == 0x01) { - if (SendCommand((uint8_t *)cfg->config, cfg->config_count) < 0) + if (SendCommand((uint8_t *)cfg->config, cfg->config_count) < 0) Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, hdr->subtype); else Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, hdr->subtype); return 0; - } - else + } + else { // this is an inquiry, so we have to send data back cfg->config_count = SendRequest((uint8_t*)cfg->config, cfg->config_count, (uint8_t*)cfg->config); @@ -896,16 +896,16 @@ } } - if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, + if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, PLAYER_PTZ_CMD_STATE, device_addr)) { - + short zoomdemand=0; bool newpantilt=true, newzoom=true; - + assert (hdr->size == sizeof (player_ptz_cmd_t)); player_ptz_cmd_t command = *reinterpret_cast<player_ptz_cmd_t *> (data); - + if(pandemand != (int)rint(RTOD(command.pan))) { pandemand = (int)rint(RTOD(command.pan)); @@ -916,17 +916,17 @@ tiltdemand = (int)rint(RTOD(command.tilt)); newpantilt = true; } - + if(zoomdemand != command.zoom) { zoomdemand = (int)command.zoom; //(int)rint(RTOD(command.zoom)); newzoom = true; } - //////////////////////////////////////////////////////////// - //zoomdemand = (1960 * (this->maxfov - zoomdemand)) / + //////////////////////////////////////////////////////////// + //zoomdemand = (1960 * (this->maxfov - zoomdemand)) / // (this->maxfov - this->minfov); //////////////////////////////////////////////////////////// - + if(newzoom) { if(SendAbsZoom(zoomdemand)) @@ -935,7 +935,7 @@ pthread_exit(NULL); } } - + if(newpantilt) { pandemand = -pandemand; @@ -945,10 +945,10 @@ pthread_exit(NULL); } // } - } + } return 0; } - + return -1; } Modified: code/player/trunk/server/drivers/ptz/ptu46.cc =================================================================== --- code/player/trunk/server/drivers/ptz/ptu46.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/ptz/ptu46.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -157,7 +157,7 @@ // read buffer char buffer[PTU46_BUFFER_LEN+1]; - int Write(char * data, int length = 0); + int Write(const char * data, int length = 0); }; @@ -288,7 +288,7 @@ } -int PTU46::Write(char * data, int length) +int PTU46::Write(const char * data, int length) { if (fd < 0) Modified: code/player/trunk/server/drivers/ptz/sonyevid30.cc =================================================================== --- code/player/trunk/server/drivers/ptz/sonyevid30.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/ptz/sonyevid30.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -488,7 +488,7 @@ virtual int SendAbsZoom(short zoom); virtual int GetAbsZoom(short* zoom); virtual int GetAbsPanTilt(short* pan, short* tilt); - virtual void PrintPacket(char* str, unsigned char* cmd, int len); + virtual void PrintPacket(const char* str, unsigned char* cmd, int len); /* * Get the current Pan/Tilt/Zoom state of the camera (and take a guess at @@ -1419,7 +1419,7 @@ } -void SonyEVID30::PrintPacket(char *str, unsigned char *cmd, int len) +void SonyEVID30::PrintPacket(const char *str, unsigned char *cmd, int len) { printf("%s: ", str); for(int i=0;i<len;i++) Modified: code/player/trunk/server/drivers/rfid/rfi341_protocol.cc =================================================================== --- code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -36,7 +36,7 @@ (char*) port, strerror (errno)); return (-1); } - + // Change port settings struct termios options; memset (&options, 0, sizeof (options));// clear the struct for new port settings @@ -62,7 +62,7 @@ // read satisfied if TIME is exceeded (t = TIME *0.1 s) // options.c_cc[VTIME] = 1; // options.c_cc[VMIN] = 0; - + // Change the baud rate switch (port_speed) { case 1200: { @@ -116,7 +116,7 @@ PLAYER_MSG1 (1, "> Connecting to SICK RFI341 at %dbps...[done]", port_speed); // Make sure queues are empty before we begin tcflush (fd, TCIOFLUSH); - + return (0); } @@ -195,21 +195,21 @@ return (-1); } } - + // Tell sensor to change the baud rate - char *c = (char*) malloc (10); + char *c = (char*) malloc (10); while (strncmp ((const char*)buffer, "1003", 4) != 0) { sprintf (c, "1003%s", transferspeed_string); SendCommand (c); ReadResult (); } - + // OK, we told the sensor to change baud rate, so let's do it also struct termios options; // clear the struct for new port settings memset (&options, 0, sizeof (options)); - + // Get the current port settings if (tcgetattr (fd, &options) != 0) { PLAYER_ERROR (">> Unable to get serial port attributes !"); @@ -235,20 +235,20 @@ return (0); } else - PLAYER_WARN1 ("> Checksum error [0x%x]!", checksum); + PLAYER_WARN1 ("> Checksum error [0x%x]!", checksum); return (-1); } //////////////////////////////////////////////////////////////////////////////// // Send a command to the rfid unit. Returns -1 on error. int - rfi341_protocol::SendCommand (char* cmd) + rfi341_protocol::SendCommand (const char* cmd) { assemblecommand ((unsigned char *) cmd, strlen (cmd)); - + if (verbose) { - printf ("--> STX "); + printf ("--> STX "); printf ("%s ", cmd); printf ("ETX 0x%x\n", command[commandlength-1]); } @@ -256,7 +256,7 @@ int n = write (fd, command, commandlength); if (n < 0) return (-1); - + return (0); } @@ -287,7 +287,7 @@ n = read (fd, &buffer[read_count], 1); checksum = buffer[read_count]; read_count += n; - + // TODO: check the checksum (that's what it's for!) buffer[read_count-2] = 0x00; bufferlength = read_count-2; @@ -296,7 +296,7 @@ { printf ("<-- STX "); printf ("%s ", buffer); - printf ("ETX 0x%X\n", checksum); + printf ("ETX 0x%X\n", checksum); } return (0); } @@ -308,21 +308,21 @@ { unsigned char checksum = 0; int index = 0; - + command[0] = STX; // Messages start with STX - + for (index = 0; index < len; index++) command[index + 1] = cmd[index]; command[1 + len] = ETX; // Messages end with ETX - + for (int i = 0; i < len+2; i++) checksum ^= command[i]; - + command[2 + len] = checksum; - + commandlength = 3 + len; - + return (0); } @@ -334,15 +334,15 @@ { char buf[17]; unsigned int hexnumber; - + // create inventory, single mode SendCommand ("6C20s"); ReadResult (); - + // get inventory SendCommand ("6C21"); ReadResult (); - + if (tags != NULL) { for (int i = 0; i < number_of_tags; i++) @@ -354,7 +354,7 @@ memcpy (buf, &buffer[4], 4); buf[4] = 0; number_of_tags = atol(buf); - + // allocate memory for the tags tags = (char**)malloc (number_of_tags*sizeof(char*)); for (int i=0; i < number_of_tags; i++) @@ -371,7 +371,7 @@ player_rfid_data_t player_data; player_data.tags_count = number_of_tags; player_data.tags = (player_rfid_tag_t*)calloc(player_data.tags_count, sizeof(player_data.tags[0])); - + player_rfid_tag_t tag; for (int i=0; i < number_of_tags; i++) { Modified: code/player/trunk/server/drivers/rfid/rfi341_protocol.h =================================================================== --- code/player/trunk/server/drivers/rfid/rfi341_protocol.h 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/rfid/rfi341_protocol.h 2008-06-17 00:13:43 UTC (rev 6597) @@ -22,26 +22,26 @@ { public: rfi341_protocol (const char* port_name, int debug_mode); - + // Creates socket, connects // Connects first at 'connect_speed' int Connect (int connect_speed); - + // but for transfer, we might want to use a different 'transfer_speed' int SetupSensor (int transfer_speed); int Disconnect (); // assembles a command and sends it on the wire - int SendCommand (char* cmd); + int SendCommand (const char* cmd); // reads the result of a query from the device int ReadResult (); player_rfid_data_t ReadTags (); - + private: // assembles STX's, message, checksum ready to be sent. Cool. int assemblecommand (unsigned char* command, int len); - + int number_of_tags; char **tags; @@ -58,7 +58,7 @@ unsigned char buffer[4096]; unsigned int bufferlength; int checksum; - + // for sending: unsigned char command[BUF_SIZE]; int commandlength; Modified: code/player/trunk/server/drivers/shell/kartowriter.cc =================================================================== --- code/player/trunk/server/drivers/shell/kartowriter.cc 2008-06-16 23:25:32 UTC (rev 6596) +++ code/player/trunk/server/drivers/shell/kartowriter.cc 2008-06-17 00:13:43 UTC (rev 6597) @@ -122,12 +122,12 @@ //destructor virtual ~LogDevice(); //prints the Device unique ID - char* getUID(); + const char* get... [truncated message content] |
From: <th...@us...> - 2008-06-16 17:49:24
|
Revision: 6599 http://playerstage.svn.sourceforge.net/playerstage/?rev=6599&view=rev Author: thjc Date: 2008-06-16 17:49:32 -0700 (Mon, 16 Jun 2008) Log Message: ----------- merged file watcher changes from 2-1 (6501,6539,6540) Modified Paths: -------------- code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/libplayercore/driver.cc code/player/trunk/libplayercore/driver.h code/player/trunk/libplayercore/globals.cc code/player/trunk/libplayercore/globals.h code/player/trunk/libplayercore/playercore.h code/player/trunk/libplayertcp/playertcp.cc code/player/trunk/libplayertcp/playerudp.cc code/player/trunk/server/drivers/blobfinder/acts/acts.cc code/player/trunk/server/drivers/opaque/tcpstream.cc code/player/trunk/server/server.cc Added Paths: ----------- code/player/trunk/libplayercore/Makefile.am code/player/trunk/libplayercore/filewatcher.cc code/player/trunk/libplayercore/filewatcher.h Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-06-17 00:49:32 UTC (rev 6599) @@ -55,6 +55,7 @@ drivertable.cc devicetable.cc configfile.cc + filewatcher.cc message.cc wallclocktime.cc plugins.cc @@ -104,6 +105,7 @@ driver.h drivertable.h error.h + filewatcher.h globals.h interface_util.h message.h Added: code/player/trunk/libplayercore/Makefile.am =================================================================== --- code/player/trunk/libplayercore/Makefile.am (rev 0) +++ code/player/trunk/libplayercore/Makefile.am 2008-06-17 00:49:32 UTC (rev 6599) @@ -0,0 +1,70 @@ +AM_CPPFLAGS = -g -Wall -D PLAYER_INSTALL_PREFIX="\"@PREFIX@\"" -I$(top_srcdir) + +# create the pkg-config entry for the server headers +pkgconfigdir = $(libdir)/pkgconfig +pkgconfig_DATA = playercore.pc playererror.pc playerutils.pc + +dist_bin_SCRIPTS = playerinterfacegen.py + +EXTRA_DIST = playercore.pc.in playererror.pc.in playerutils.pc.in interfaces/ADDING_INTERFACES $(shell find $(srcdir)/interfaces -name "*.def") + +BUILT_SOURCES = playerconfig.h player_interfaces.h interface_table.c +CLEANFILES = playercore.pc playererror.pc playerutils.pc +DISTCLEANFIELS = $BUILT_SOURCES + +lib_LTLIBRARIES = libplayererror.la libplayerutils.la libplayercore.la + +libplayercore_la_SOURCES = driver.cc driver.h \ + device.cc device.h \ + drivertable.h drivertable.cc \ + devicetable.h devicetable.cc \ + configfile.cc configfile.h \ + playercommon.h player.h playerconfig.h.in \ + message.h message.cc \ + filewatcher.cc filewatcher.h \ + wallclocktime.cc wallclocktime.h playertime.h \ + plugins.cc plugins.h \ + globals.cc globals.h \ + property.cpp property.h +libplayercore_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir) $(top_builddir)/libplayercore/libplayererror.la $(top_builddir)/libplayercore/libplayerutils.la +libplayercore_la_DEPENDENCIES = $(top_builddir)/libplayercore/libplayererror.la $(top_builddir)/libplayercore/libplayerutils.la $(top_builddir)/libplayercore/player_interfaces.h + +libplayererror_la_SOURCES = error.h error.c +libplayererror_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir) + +libplayerutils_la_SOURCES = interface_util.c interface_util.h \ + addr_util.c addr_util.h +libplayerutils_la_LDFLAGS = $(PLAYER_VERSION_INFO) -rpath $(libdir) +libplayerutils_la_DEPENDENCIES = interface_table.c + + +coreincludedir = $(includedir)/player-$(PLAYER_MAJOR_VERSION).$(PLAYER_MINOR_VERSION)/libplayercore +coreinclude_HEADERS = configfile.h \ + device.h \ + devicetable.h \ + driver.h \ + drivertable.h \ + filewatcher.h \ + globals.h \ + interface_util.h \ + message.h \ + player.h \ + playercommon.h \ + playerconfig.h \ + playercore.h \ + playertime.h \ + plugins.h \ + wallclocktime.h \ + error.h \ + addr_util.h \ + property.h \ + player_interfaces.h + +player_interfaces.h: $(srcdir)/interfaces/* playerinterfacegen.py + python $(srcdir)/playerinterfacegen.py > $(builddir)/player_interfaces.h +# if ! ./playerinterfacegen.py > player_interfaces.h; then rm player_interfaces.h; fi + +interface_table.c: $(srcdir)/interfaces/* playerinterfacegen.py + python $(srcdir)/playerinterfacegen.py --utils > $(top_builddir)/libplayercore/interface_table.c +# if ! ./playerinterfacegen.py --utils > interface_table.c; then rm interface_table.c; fi + Modified: code/player/trunk/libplayercore/driver.cc =================================================================== --- code/player/trunk/libplayercore/driver.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/driver.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -61,6 +61,7 @@ #include <libplayercore/devicetable.h> #include <libplayercore/configfile.h> #include <libplayercore/globals.h> +#include <libplayercore/filewatcher.h> #include <libplayercore/property.h> #include <libplayercore/interface_util.h> @@ -226,10 +227,10 @@ } void -Driver::Publish(player_devaddr_t addr, - uint8_t type, +Driver::Publish(player_devaddr_t addr, + uint8_t type, uint8_t subtype, - void* src, + void* src, size_t deprecated, double* timestamp, bool copy) @@ -302,6 +303,19 @@ return( shutdownResult ); } +/** @brief Wake up the driver if the specified event occurs on the file descriptor */ +int Driver::AddFileWatch(int fd, bool ReadWatch , bool WriteWatch , bool ExceptWatch ) +{ + return fileWatcher->AddFileWatch(fd,InQueue,ReadWatch,WriteWatch,ExceptWatch); +} + +/** @brief Remove a previously added watch, call with the same arguments as when adding the watch */ +int Driver::RemoveFileWatch(int fd, bool ReadWatch , bool WriteWatch , bool ExceptWatch ) +{ + return fileWatcher->RemoveFileWatch(fd,InQueue,ReadWatch,WriteWatch,ExceptWatch); +} + + /* start a thread that will invoke Main() */ void Driver::StartThread(void) Modified: code/player/trunk/libplayercore/driver.h =================================================================== --- code/player/trunk/libplayercore/driver.h 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/driver.h 2008-06-17 00:49:32 UTC (rev 6599) @@ -146,7 +146,7 @@ @returns 0 on success, non-zero otherwise. */ int AddInterface(player_devaddr_t *addr, ConfigFile * cf, int section, int code, char * key = NULL); - + /** @brief Set/reset error code */ void SetError(int code) {this->error = code;} @@ -154,13 +154,20 @@ Call this method to block until a new message arrives on Driver::InQueue. This method will return true immediately if at least - one message is already waiting. - + one message is already waiting. + If TimeOut is set to a positive value this method will return false if the timeout occurs before and update is recieved. */ bool Wait(double TimeOut=0.0) { return this->InQueue->Wait(); } + /** @brief Wake up the driver if the specified event occurs on the file descriptor */ + int AddFileWatch(int fd, bool ReadWatch = true, bool WriteWatch = false, bool ExceptWatch = true); + + /** @brief Remove a previously added watch, call with the same arguments as when adding the watch */ + int RemoveFileWatch(int fd, bool ReadWatch = true, bool WriteWatch = false, bool ExceptWatch = true); + + public: /** @brief The driver's thread. @@ -203,10 +210,10 @@ bool copy=true); /** @brief Publish a message via one of this driver's interfaces. - + This form of Publish will assemble the message header for you. The message is broadcast to all interested parties - + @param addr The origin address @param type The message type @param subtype The message subtype @@ -215,23 +222,23 @@ @param timestamp Timestamp for the message body (if NULL, then the current time will be filled in) @param copy if set to false the data will be claimed and the caller should no longer use or free it */ - virtual void Publish(player_devaddr_t addr, - uint8_t type, + virtual void Publish(player_devaddr_t addr, + uint8_t type, uint8_t subtype, - void* src=NULL, + void* src=NULL, size_t deprecated=0, double* timestamp=NULL, bool copy=true); - - + + /** @brief Publish a message via one of this driver's interfaces. Use this form of Publish if you already have the message header assembled and have a target queue to send to. @param queue the target queue. @param hdr The message header - @param src The message body + @param src The message body @param copy if set to false the data will be claimed and the caller should no longer use or free it */ virtual void Publish(QueuePointer &queue, player_msghdr_t* hdr, @@ -243,8 +250,8 @@ Use this form of Publish if you already have the message header assembled and wish to broadcast the message to all subscribed parties. @param hdr The message header - @param src The message body - @param copy if set to false the data will be claimed and the caller should no longer use or free it */ + @param src The message body + @param copy if set to false the data will be claimed and the caller should no longer use or free it */ virtual void Publish(player_msghdr_t* hdr, void* src, bool copy = true); @@ -321,15 +328,15 @@ subscriptions to the driver; a driver MAY override them, but usually won't. This alternative form includes the clients queue so you can map future requests and unsubscriptions to a specific queue. - + If this methods returns a value other than 1 then the other form of subscribe wont be called @param queue The queue of the subscribing client @param addr Address of the device to subscribe to (the driver may have more than one interface). @returns Returns 0 on success, -ve on error and 1 for unimplemented. */ - virtual int Subscribe(QueuePointer &queue, player_devaddr_t addr) {return 1;}; - + virtual int Subscribe(QueuePointer &queue, player_devaddr_t addr) {return 1;}; + /** @brief Unsubscribe from this driver. The Subscribe() and Unsubscribe() methods are used to control @@ -347,7 +354,7 @@ subscriptions to the driver; a driver MAY override them, but usually won't.This alternative form includes the clients queue so you can map future requests and unsubscriptions to a specific queue. - + If this methods returns a value other than 1 then the other form of subscribe wont be called @param queue The queue of the subscribing client @@ -355,7 +362,7 @@ have more than one interface). @returns Returns 0 on success. */ virtual int Unsubscribe(QueuePointer &queue, player_devaddr_t addr) {return 1;}; - + /** @brief Initialize the driver. This function is called with the first client subscribes; it MUST @@ -447,7 +454,6 @@ @param section Configuration file section that may define the property value @return True if the property was registered, false otherwise */ virtual bool RegisterProperty(Property *prop, ConfigFile* cf, int section); - }; Added: code/player/trunk/libplayercore/filewatcher.cc =================================================================== --- code/player/trunk/libplayercore/filewatcher.cc (rev 0) +++ code/player/trunk/libplayercore/filewatcher.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -0,0 +1,192 @@ +/* + * FileWatcher.cc + * + * Created on: 10/06/2008 + * Author: tcollett + */ + +#include <libplayercore/filewatcher.h> +#include <libplayercore/message.h> +#include <libplayercore/error.h> +#include <sys/time.h> +#include <stdlib.h> +#include <assert.h> +#include <error.h> +#include <math.h> +#include <string.h> + +FileWatcher::FileWatcher() +{ + WatchedFilesArraySize = INITIAL_WATCHED_FILES_ARRAY_SIZE; + WatchedFilesArrayCount = 0; + WatchedFiles = reinterpret_cast<struct fd_driver_pair *> (calloc(WatchedFilesArraySize,sizeof(WatchedFiles[0]))); + assert(WatchedFiles); + pthread_mutex_init(&this->lock,NULL); + +} + +FileWatcher::~FileWatcher() +{ + free(WatchedFiles); +} + +void FileWatcher::Lock() +{ + pthread_mutex_lock(&lock); +} + +void FileWatcher::Unlock() +{ + pthread_mutex_unlock(&lock); +} + + +int FileWatcher::Wait(double Timeout) +{ + Lock(); + if (WatchedFilesArrayCount == 0) + { + Unlock(); + return 0; + } + + // intialise our FD sets for the select call + fd_set ReadFds,WriteFds,ExceptFds; + FD_ZERO(&ReadFds); + FD_ZERO(&WriteFds); + FD_ZERO(&ExceptFds); + + int maxfd = 0; + + for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii) + { + if (WatchedFiles[ii].fd >= 0) + { + if (WatchedFiles[ii].fd > maxfd) + maxfd = WatchedFiles[ii].fd; + if (WatchedFiles[ii].Read) + FD_SET(WatchedFiles[ii].fd,&ReadFds); + if (WatchedFiles[ii].Write) + FD_SET(WatchedFiles[ii].fd,&WriteFds); + if (WatchedFiles[ii].Except) + FD_SET(WatchedFiles[ii].fd,&ExceptFds); + } + } + + struct timeval t; + t.tv_sec = static_cast<int> (floor(Timeout)); + t.tv_usec = static_cast<int> ((Timeout - static_cast<int> (floor(Timeout))) * 1e6); + Unlock(); + + int ret = select (maxfd+1,&ReadFds,&WriteFds,&ExceptFds,&t); + + if (ret < 0) + { + PLAYER_ERROR2("Select called failed in File Watcher: %d %s",errno,strerror(errno)); + return ret; + } + + int queueless_count = 0; + + Lock(); + for (unsigned int ii = 0; ii < WatchedFilesArrayCount && static_cast<int> (ii) < maxfd; ++ii) + { + int fd = WatchedFiles[ii].fd; + QueuePointer &q = WatchedFiles[ii].queue; + if (fd > 0 && fd <= maxfd) + { + if ((WatchedFiles[ii].Read && FD_ISSET(fd,&ReadFds)) || + (WatchedFiles[ii].Write && FD_ISSET(fd,&WriteFds)) || + (WatchedFiles[ii].Except && FD_ISSET(fd,&ExceptFds))) + { + if (q != NULL) + { + q->DataAvailable(); + } + else + queueless_count++; + + } + } + } + Unlock(); + + return queueless_count; +} + +int FileWatcher::AddFileWatch(int fd, bool WatchRead, bool WatchWrite, bool WatchExcept) +{ + QueuePointer q; + return AddFileWatch(fd, q,WatchRead,WatchWrite,WatchExcept); +} + + +int FileWatcher::AddFileWatch(int fd, QueuePointer & queue, bool WatchRead, bool WatchWrite, bool WatchExcept) +{ + Lock(); + fprintf(stderr,"Added file watch %d \n",fd); + // find the first available file descriptor + struct fd_driver_pair *next_entry = NULL; + if (WatchedFilesArrayCount < WatchedFilesArraySize) + { + next_entry = &WatchedFiles[WatchedFilesArrayCount]; + WatchedFilesArrayCount++; + } + else + { + // first see if there is an empty spot in the list + for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii) + { + if (WatchedFiles[ii].fd < 0) + { + next_entry = &WatchedFiles[ii]; + break; + } + } + if (next_entry == NULL) + { + // otherwise we allocate some more room for the array + WatchedFilesArraySize*=2; + WatchedFiles = reinterpret_cast<struct fd_driver_pair *> (realloc(WatchedFiles,sizeof(WatchedFiles[0])*WatchedFilesArraySize)); + next_entry = &WatchedFiles[WatchedFilesArrayCount]; + + } + } + + next_entry->fd = fd; + next_entry->queue = queue; + next_entry->Read = WatchRead; + next_entry->Write = WatchWrite; + next_entry->Except = WatchExcept; + Unlock(); + return 0; +} + +int FileWatcher::RemoveFileWatch(int fd, bool WatchRead, bool WatchWrite, bool WatchExcept) +{ + QueuePointer q; + return RemoveFileWatch(fd, q,WatchRead,WatchWrite,WatchExcept); +} + + +int FileWatcher::RemoveFileWatch(int fd, QueuePointer &queue, bool WatchRead, bool WatchWrite, bool WatchExcept) +{ + Lock(); + // this finds the first matching entry and removes it. It only removes one entry so call remove for every add + for (unsigned int ii = 0; ii < WatchedFilesArrayCount; ++ii) + { + if (WatchedFiles[ii].fd == fd && + WatchedFiles[ii].queue == queue && + WatchedFiles[ii].Read == WatchRead && + WatchedFiles[ii].Write == WatchWrite && + WatchedFiles[ii].Except == WatchExcept) + { + WatchedFiles[ii].fd = -1; + Unlock(); + return 0; + } + } + Unlock(); + return -1; +} + Added: code/player/trunk/libplayercore/filewatcher.h =================================================================== --- code/player/trunk/libplayercore/filewatcher.h (rev 0) +++ code/player/trunk/libplayercore/filewatcher.h 2008-06-17 00:49:32 UTC (rev 6599) @@ -0,0 +1,56 @@ +/* + * filewatcher.h + * + * Created on: 10/06/2008 + * Author: tcollett + */ + +#ifndef FILEWATCHER_H_ +#define FILEWATCHER_H_ + +#include <sys/select.h> +#include <sys/types.h> +#include <stdlib.h> +#include <pthread.h> +#include <libplayercore/message.h> + +class MessageQueue; + +struct fd_driver_pair +{ + int fd; + QueuePointer queue; + bool Read; + bool Write; + bool Except; +}; + +const size_t INITIAL_WATCHED_FILES_ARRAY_SIZE = 32; + +class FileWatcher +{ +public: + FileWatcher(); + virtual ~FileWatcher(); + + int Wait(double Timeout = 0); + int AddFileWatch(int fd, QueuePointer & queue, bool WatchRead = true, bool WatchWrite = false, bool WatchExcept = true); + int RemoveFileWatch(int fd, QueuePointer & queue, bool WatchRead = true, bool WatchWrite = false, bool WatchExcept = true); + int AddFileWatch(int fd, bool WatchRead = true, bool WatchWrite = false, bool WatchExcept = true); + int RemoveFileWatch(int fd, bool WatchRead = true, bool WatchWrite = false, bool WatchExcept = true); + +private: + struct fd_driver_pair * WatchedFiles; + size_t WatchedFilesArraySize; + size_t WatchedFilesArrayCount; + + /** @brief Lock access to watcher internals. */ + virtual void Lock(void); + /** @brief Unlock access to watcher internals. */ + virtual void Unlock(void); + /// Used to lock access to Data. + pthread_mutex_t lock; + +}; + +#endif /* FILEWATCHER_H_ */ Modified: code/player/trunk/libplayercore/globals.cc =================================================================== --- code/player/trunk/libplayercore/globals.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/globals.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -47,6 +47,7 @@ #include <libplayercore/devicetable.h> #include <libplayercore/drivertable.h> +#include <libplayercore/filewatcher.h> #include <libplayercore/playertime.h> #include <libplayercore/wallclocktime.h> @@ -60,11 +61,14 @@ // this table holds all the currently *available* drivers DriverTable* driverTable; -// the global PlayerTime object has a method +// the global PlayerTime object has a method // int GetTime(struct timeval*) // which everyone must use to get the current time PlayerTime* GlobalTime; +// global class for watching for changes in files and sockets +FileWatcher* fileWatcher; + char playerversion[32]; bool player_quit; @@ -84,6 +88,7 @@ deviceTable = new DeviceTable(); driverTable = new DriverTable(); GlobalTime = new WallclockTime(); + fileWatcher = new FileWatcher(); strncpy(playerversion, PLAYER_VERSION, sizeof(playerversion)); player_quit = false; player_quiet_startup = false; @@ -95,12 +100,10 @@ void player_globals_fini() { - if(deviceTable) - delete deviceTable; - if(driverTable) - delete driverTable; - if(GlobalTime) - delete GlobalTime; + delete deviceTable; + delete driverTable; + delete GlobalTime; + delete fileWatcher; #if HAVE_PLAYERSD if(globalSD) player_sd_fini(globalSD); Modified: code/player/trunk/libplayercore/globals.h =================================================================== --- code/player/trunk/libplayercore/globals.h 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/globals.h 2008-06-17 00:49:32 UTC (rev 6599) @@ -44,11 +44,13 @@ class DeviceTable; class PlayerTime; class DriverTable; +class FileWatcher; struct player_sd; extern DeviceTable* deviceTable; extern PlayerTime* GlobalTime; extern DriverTable* driverTable; +extern FileWatcher* fileWatcher; extern char playerversion[]; extern bool player_quit; extern bool player_quiet_startup; Modified: code/player/trunk/libplayercore/playercore.h =================================================================== --- code/player/trunk/libplayercore/playercore.h 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayercore/playercore.h 2008-06-17 00:49:32 UTC (rev 6599) @@ -46,6 +46,7 @@ #include <libplayercore/driver.h> #include <libplayercore/drivertable.h> #include <libplayercore/error.h> +#include <libplayercore/filewatcher.h> #include <libplayercore/globals.h> #include <libplayercore/interface_util.h> #include <libplayercore/message.h> Modified: code/player/trunk/libplayertcp/playertcp.cc =================================================================== --- code/player/trunk/libplayertcp/playertcp.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayertcp/playertcp.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -187,6 +187,9 @@ // set up for later use of poll() to accept() connections on this port this->listen_ufds[i].fd = this->listeners[i].fd; this->listen_ufds[i].events = POLLIN; + + // set up for later use by global file watcher + fileWatcher->AddFileWatch(this->listeners[i].fd); } return(0); @@ -246,6 +249,10 @@ this->client_ufds[j].fd = this->clients[j].fd; this->client_ufds[j].events = POLLIN; + // set up for later use by global file watcher + fileWatcher->AddFileWatch(this->client_ufds[j].fd); + + // Create an outgoing queue for this client this->clients[j].queue = QueuePointer(true,PLAYER_MSGQUEUE_DEFAULT_MAXLEN); @@ -388,6 +395,8 @@ free(this->clients[cli].dev_subs); if(close(this->clients[cli].fd) < 0) PLAYER_WARN1("close() failed: %s", strerror(errno)); + fileWatcher->RemoveFileWatch(this->clients[cli].fd); + this->clients[cli].fd = -1; this->clients[cli].valid = 0; this->clients[cli].queue = QueuePointer(); Modified: code/player/trunk/libplayertcp/playerudp.cc =================================================================== --- code/player/trunk/libplayertcp/playerudp.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/libplayertcp/playerudp.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -174,6 +174,10 @@ // set up for later use of poll() to accept() connections on this port this->listen_ufds[i].fd = this->listeners[i].fd; this->listen_ufds[i].events = POLLIN; + + // set up for later use by global file watcher + fileWatcher->AddFileWatch(this->listeners[i].fd); + } return(0); @@ -269,6 +273,7 @@ } } free(this->clients[cli].dev_subs); + fileWatcher->RemoveFileWatch(this->clients[cli].fd); this->clients[cli].fd = -1; this->clients[cli].valid = 0; // FIXME Modified: code/player/trunk/server/drivers/blobfinder/acts/acts.cc =================================================================== --- code/player/trunk/server/drivers/blobfinder/acts/acts.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/server/drivers/blobfinder/acts/acts.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -430,7 +430,7 @@ // returns the enum representation of the given version string, or // -1 on failure to match. -acts_version_t Acts::version_string_to_enum(char* versionstr) +acts_version_t Acts::version_string_to_enum(const char* versionstr) { if(!strcmp(versionstr,ACTS_VERSION_1_0_STRING)) return(ACTS_VERSION_1_0); @@ -497,103 +497,121 @@ // build the argument list, based on version switch(acts_version) { - case ACTS_VERSION_1_0: - acts_args[i++] = "-t"; + // these are needed as execv expects a const array of char *'s not an array of const char *'s + static char dash_d[3] = "-d"; + static char dash_i[3] = "-i"; + static char dash_n[3] = "-n"; + static char dash_p[3] = "-p"; + static char dash_s[3] = "-s"; + static char dash_t[3] = "-t"; + static char dash_w[3] = "-w"; + static char dash_x[3] = "-x"; + + static char dash_B[3] = "-B"; + static char dash_C[3] = "-C"; + static char dash_G[3] = "-G"; + static char dash_H[3] = "-H"; + static char dash_R[3] = "-R"; + static char dash_V[3] = "-V"; + static char dash_W[3] = "-W"; + + case ACTS_VERSION_1_0: + acts_args[i++] = dash_t; acts_args[i++] = configfilepath; if(strlen(portnumstring)) { - acts_args[i++] = "-s"; + acts_args[i++] = dash_s; acts_args[i++] = portnumstring; } if(strlen(devicepath)) { - acts_args[i++] = "-d"; + acts_args[i++] = dash_d; acts_args[i++] = devicepath; } break; case ACTS_VERSION_1_2: - acts_args[i++] = "-t"; + acts_args[i++] = dash_t; acts_args[i++] = configfilepath; if(strlen(portnumstring)) { - acts_args[i++] = "-p"; + acts_args[i++] = dash_p; acts_args[i++] = portnumstring; } if(strlen(devicepath)) { - acts_args[i++] = "-d"; + acts_args[i++] = dash_d; acts_args[i++] = devicepath; } if(strlen(contrast)) { - acts_args[i++] = "-C"; + acts_args[i++] = dash_C; acts_args[i++] = contrast; } if(strlen(brightness)) { - acts_args[i++] = "-B"; + acts_args[i++] = dash_B; acts_args[i++] = brightness; } - acts_args[i++] = "-W"; + acts_args[i++] = dash_W; acts_args[i++] = widthstring; - acts_args[i++] = "-H"; + acts_args[i++] = dash_H; acts_args[i++] = heightstring; break; case ACTS_VERSION_2_0: - acts_args[i++] = "-t"; + acts_args[i++] = dash_t; acts_args[i++] = configfilepath; if(strlen(minarea)) { - acts_args[i++] = "-w"; + acts_args[i++] = dash_w; acts_args[i++] = minarea; } if(strlen(portnumstring)) { - acts_args[i++] = "-p"; + acts_args[i++] = dash_p; acts_args[i++] = portnumstring; } if(strlen(fps)) { - acts_args[i++] = "-R"; + acts_args[i++] = dash_R; acts_args[i++] = fps; } if(strlen(drivertype)) { - acts_args[i++] = "-G"; + acts_args[i++] = dash_G; acts_args[i++] = drivertype; } if(invertp > 0) - acts_args[i++] = "-i"; + acts_args[i++] = dash_i; if(strlen(devicepath)) { - acts_args[i++] = "-d"; + acts_args[i++] = dash_d; acts_args[i++] = devicepath; } if(strlen(channel)) { - acts_args[i++] = "-n"; + acts_args[i++] = dash_n; acts_args[i++] = channel; } if(strlen(norm)) { - acts_args[i++] = "-V"; + acts_args[i++] = dash_V; acts_args[i++] = norm; } if(pxc200p > 0) - acts_args[i++] = "-x"; + acts_args[i++] = dash_x; if(strlen(brightness)) { - acts_args[i++] = "-B"; + acts_args[i++] = dash_B; acts_args[i++] = brightness; } if(strlen(contrast)) { - acts_args[i++] = "-C"; + acts_args[i++] = dash_C; acts_args[i++] = contrast; } - acts_args[i++] = "-W"; + acts_args[i++] = dash_W; acts_args[i++] = widthstring; - acts_args[i++] = "-H"; + acts_args[i++] = dash_H; acts_args[i++] = heightstring; break; case ACTS_VERSION_UNKNOWN: Modified: code/player/trunk/server/drivers/opaque/tcpstream.cc =================================================================== --- code/player/trunk/server/drivers/opaque/tcpstream.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/server/drivers/opaque/tcpstream.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -112,22 +112,10 @@ #include <libplayercore/playercore.h> #define DEFAULT_TCP_OPAQUE_BUFFER_SIZE 4096 -#define DEFAULT_TCP_OPAQUE_IP "10.99.10.6" +#define DEFAULT_TCP_OPAQUE_IP "127.0.0.1" #define DEFAULT_TCP_OPAQUE_PORT 4002 //////////////////////////////////////////////////////////////////////////////// -// Device codes - -#define STX 0x02 -#define ACK 0xA0 -#define NACK 0x92 -#define CRC16_GEN_POL 0x8005 - -//////////////////////////////////////////////////////////////////////////////// -// Error macros -#define RETURN_ERROR(erc, m) {PLAYER_ERROR(m); return erc;} - -//////////////////////////////////////////////////////////////////////////////// // The class for the driver class TCPStream : public Driver { @@ -166,13 +154,7 @@ int sock; uint8_t * rx_buffer; - //unsigned int rx_buffer_size; - struct termios oldtio; - - // opaque device file descriptor - //int opaque_fd; - // Properties IntProperty buffer_size; StringProperty ip; @@ -314,8 +296,7 @@ // The main loop; interact with the device here for(;;) { - // test if we are supposed to cancel - pthread_testcancel(); + Wait(1); // Process incoming messages. TCPStream::ProcessMessage() is // called on each message. @@ -323,17 +304,14 @@ if (connected) { - // Reads the data from the tcp server and then publishes it - ReadData(); + // Reads the data from the tcp server and then publishes it + ReadData(); } else { - PLAYER_MSG0(2, "TCP reconnecting"); - OpenTerm(); + PLAYER_MSG0(2, "TCP reconnecting"); + OpenTerm(); } - - // Sleep (you might, for example, block on a read() instead) - usleep(1000); } } @@ -371,7 +349,9 @@ // int TCPStream::CloseTerm() { + RemoveFileWatch(sock); close(sock); + connected = false; return 0; } Modified: code/player/trunk/server/server.cc =================================================================== --- code/player/trunk/server/server.cc 2008-06-17 00:27:13 UTC (rev 6598) +++ code/player/trunk/server/server.cc 2008-06-17 00:49:32 UTC (rev 6599) @@ -2,8 +2,8 @@ * Player - One Hell of a Robot Server * Copyright (C) 2005 - * Brian Gerkey - * * + * * This program is free software; you can redistribute it and/or modify * it under the terms of the GNU General Public License as published by * the Free Software Foundation; either version 2 of the License, or @@ -109,7 +109,7 @@ void PrintVersion(); void PrintCopyrightMsg(); void PrintUsage(); -int ParseArgs(int* port, int* debuglevel, +int ParseArgs(int* port, int* debuglevel, char** cfgfilename, int* gz_serverid, int argc, char** argv); void Quit(int signum); @@ -145,7 +145,7 @@ PLAYER_ERROR1("signal() failed: %s", strerror(errno)); exit(-1); } - + player_globals_init(); player_register_drivers(); playerxdr_ftable_init(); @@ -293,6 +293,9 @@ while(!player_quit) { + // wait until something other than driver requested watches happens + fileWatcher->Wait(); + if(ptcp->Accept(0) < 0) { PLAYER_ERROR("failed while accepting new TCP connections"); @@ -363,7 +366,7 @@ fprintf(stderr,"* Player comes with ABSOLUTELY NO WARRANTY. This is free software, and you\n* are welcome to redistribute it under certain conditions; see COPYING\n* for details.\n\n"); } -void +void PrintUsage() { int maxlen=66; @@ -394,13 +397,13 @@ } -int +int ParseArgs(int* port, int* debuglevel, char** cfgfilename, int* gz_serverid, int argc, char** argv) { int ch; const char* optflags = "d:p:hq"; - + // Get letter options while((ch = getopt(argc, argv, optflags)) != -1) { @@ -417,7 +420,7 @@ break; case '?': case ':': - case 'h': + case 'h': default: return(-1); } @@ -425,7 +428,7 @@ if(optind >= argc) return(-1); - + *cfgfilename = argv[optind]; return(0); This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <th...@us...> - 2008-06-16 17:56:38
|
Revision: 6601 http://playerstage.svn.sourceforge.net/playerstage/?rev=6601&view=rev Author: thjc Date: 2008-06-16 17:56:39 -0700 (Mon, 16 Jun 2008) Log Message: ----------- merged multiple small fixes from 2-1 (6541,6542,6543) Modified Paths: -------------- code/player/trunk/libplayercore/device.cc code/player/trunk/server/drivers/laser/sicks3000.cc code/player/trunk/server/drivers/opaque/tcpstream.cc Modified: code/player/trunk/libplayercore/device.cc =================================================================== --- code/player/trunk/libplayercore/device.cc 2008-06-17 00:52:14 UTC (rev 6600) +++ code/player/trunk/libplayercore/device.cc 2008-06-17 00:56:39 UTC (rev 6601) @@ -287,11 +287,11 @@ { resp_queue->Wait(); // HACK: this loop should not be neccesary! + // pthread_cond_wait does not garuntee no false wake up, so maybe it is. while(!(msg = resp_queue->Pop())) { - pthread_testcancel(); PLAYER_WARN("empty queue after waiting!"); - resp_queue->Wait(); + resp_queue->Wait(); // this is a cancelation point } } else Modified: code/player/trunk/server/drivers/laser/sicks3000.cc =================================================================== --- code/player/trunk/server/drivers/laser/sicks3000.cc 2008-06-17 00:52:14 UTC (rev 6600) +++ code/player/trunk/server/drivers/laser/sicks3000.cc 2008-06-17 00:56:39 UTC (rev 6601) @@ -211,7 +211,7 @@ //////////////////////////////////////////////////////////////////////////////// // Constructor SickS3000::SickS3000(ConfigFile* cf, int section) - : Driver(cf, section, true, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_LASER_CODE), mirror("mirror", 0, 0) + : Driver(cf, section, false, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_LASER_CODE), mirror("mirror", 0, 0) { rx_count = 0; Modified: code/player/trunk/server/drivers/opaque/tcpstream.cc =================================================================== --- code/player/trunk/server/drivers/opaque/tcpstream.cc 2008-06-17 00:52:14 UTC (rev 6600) +++ code/player/trunk/server/drivers/opaque/tcpstream.cc 2008-06-17 00:56:39 UTC (rev 6601) @@ -296,12 +296,7 @@ // The main loop; interact with the device here for(;;) { - Wait(1); - - // Process incoming messages. TCPStream::ProcessMessage() is - // called on each message. - ProcessMessages(); - + // we read/connect first otherwise we we wait when we have no data connection if (connected) { // Reads the data from the tcp server and then publishes it @@ -312,6 +307,11 @@ PLAYER_MSG0(2, "TCP reconnecting"); OpenTerm(); } + + PLAYER_MSG1(2, "TCP Main loop running (%d)",device_addr.index); + Wait(1); + + ProcessMessages(); } } This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-06-16 18:23:31
|
Revision: 6607 http://playerstage.svn.sourceforge.net/playerstage/?rev=6607&view=rev Author: gbiggs Date: 2008-06-16 18:23:36 -0700 (Mon, 16 Jun 2008) Log Message: ----------- Fixed some bad paths, cleaned up glut check for pmap. Modified Paths: -------------- code/player/trunk/client_libs/libplayerc/CMakeLists.txt code/player/trunk/cmake/internal/SearchForStuff.cmake code/player/trunk/config.h.in code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/libplayertcp/CMakeLists.txt code/player/trunk/replace/clock_gettime.c code/player/trunk/server/libplayerdrivers/CMakeLists.txt code/player/trunk/utils/pmap/CMakeLists.txt code/player/trunk/utils/pmap/lodo.cpp code/player/trunk/utils/pmap/omap.cpp code/player/trunk/utils/pmap/pmap.cpp code/player/trunk/utils/pmap/pmap_test.cpp code/player/trunk/utils/pmap/rmap.cpp Modified: code/player/trunk/client_libs/libplayerc/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-06-17 01:23:36 UTC (rev 6607) @@ -49,9 +49,9 @@ dev_vectormap.c dev_wifi.c dev_wsn.c) -IF(NOT HAVE_POLL) - SET(playercSrcs ${playercSrcs} ../../replace/poll.c) -ENDIF(NOT HAVE_POLL) +IF (NOT HAVE_POLL) + SET (playercSrcs ${playercSrcs} ${PROJECT_SOURCE_DIR}/replace/poll.c) +ENDIF (NOT HAVE_POLL) APPEND_TO_CACHED_LIST (PLAYERC_EXTRA_LINK_LIBRARIES "Libs to link to with playerc" z m) PLAYER_ADD_LIBRARY (playerc ${playercSrcs}) Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake =================================================================== --- code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-06-17 01:23:36 UTC (rev 6607) @@ -7,9 +7,6 @@ CHECK_FUNCTION_EXISTS (cfmakeraw HAVE_CFMAKERAW) CHECK_FUNCTION_EXISTS (dirname HAVE_DIRNAME) CHECK_FUNCTION_EXISTS (getaddrinfo HAVE_GETADDRINFO) -CHECK_LIBRARY_EXISTS (GL glBegin "" HAVE_LIBGL) -CHECK_LIBRARY_EXISTS (GLU main "" HAVE_LIBGLU) -CHECK_LIBRARY_EXISTS (glut main "" HAVE_LIBGLUT) CHECK_LIBRARY_EXISTS (ltdl lt_dlopenext "" HAVE_LIBLTDL) CHECK_INCLUDE_FILES (linux/joystick.h HAVE_LINUX_JOYSTICK_H) CHECK_FUNCTION_EXISTS (poll HAVE_POLL) Modified: code/player/trunk/config.h.in =================================================================== --- code/player/trunk/config.h.in 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/config.h.in 2008-06-17 01:23:36 UTC (rev 6607) @@ -13,9 +13,6 @@ //#cmakedefine HAVE_JPEGLIB_H 1 //#cmakedefine HAVE_LIBJPEG 1 #cmakedefine HAVE_JPEG 1 -#cmakedefine HAVE_LIBGL 1 -#cmakedefine HAVE_LIBGLU 1 -#cmakedefine HAVE_LIBGLUT 1 #cmakedefine HAVE_LIBZ 1 #cmakedefine HAVE_LINUX_JOYSTICK_H 1 #cmakedefine HAVE_STDLIB_H 1 Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-06-17 01:23:36 UTC (rev 6607) @@ -40,63 +40,65 @@ ADD_CUSTOM_COMMAND (OUTPUT ${playerxdr_h} ${playerxdr_c} COMMAND ${PYTHON_EXECUTABLE} ${PROJECT_SOURCE_DIR}/libplayerxdr/playerxdrgen.py -distro ${CMAKE_CURRENT_SOURCE_DIR}/player.h ${playerxdr_c} ${playerxdr_h} ${CMAKE_CURRENT_BINARY_DIR}/player_interfaces.h WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - DEPENDS ${interfaceFiles} ${CMAKE_CURRENT_BINARY_DIR}/player_interfaces.h -) + DEPENDS ${interfaceFiles} ${CMAKE_CURRENT_BINARY_DIR}/player_interfaces.h) # Include from the binary dir to get player_interfaces.h and interface_table.h INCLUDE_DIRECTORIES (${CMAKE_CURRENT_BINARY_DIR}) +SET (playercoreSrcs driver.cc + device.cc + drivertable.cc + devicetable.cc + configfile.cc + filewatcher.cc + message.cc + wallclocktime.cc + plugins.cc + globals.cc + property.cpp) + # TODO: playerxdr should NOT be linked here; it's a bogus dependency coming # from the fact that message cloning functions are auto-generated into # playerxdr and used here. Those functions should go into a separate # library. -SET(playercore_srcs driver.cc - device.cc - drivertable.cc - devicetable.cc - configfile.cc - filewatcher.cc - message.cc - wallclocktime.cc - plugins.cc - globals.cc - property.cpp) -SET(CORELIBS playerutils playererror playerxdr pthread) -SET(CORE_PC_LIBS "-lpthread") +SET (coreLibs playerutils playererror playerxdr pthread) +SET (corePCLibs "-lpthread") PLAYER_ADD_LINK_LIB (pthread) -IF(HAVE_CLOCK_GETTIME) - SET(CORELIBS ${CORELIBS} rt) - SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lrt") +IF (HAVE_CLOCK_GETTIME) + SET (coreLibs ${coreLibs} rt) + SET (corePCLibs "${corePCLibs} -lrt") PLAYER_ADD_LINK_LIB (rt) -ELSE(HAVE_CLOCK_GETTIME) - SET(playercore_srcs ${playercore_srcs} ../replace/clock_gettime.c) -ENDIF(HAVE_CLOCK_GETTIME) -IF(HAVE_LIBLTDL) - SET(CORELIBS ${CORELIBS} ltdl dl) - SET(CORE_PC_LIBS "${CORE_PC_LIBS} -lltdl -dl") +ELSE (HAVE_CLOCK_GETTIME) + SET (playercoreSrcs ${playercoreSrcs} ${PROJECT_SOURCE_DIR}/replace/clock_gettime.c) +ENDIF (HAVE_CLOCK_GETTIME) +IF (HAVE_LIBLTDL) + SET (coreLibs ${coreLibs} ltdl dl) + SET (corePCLibs "${corePCLibs} -lltdl -dl") PLAYER_ADD_LINK_LIB (ltdl dl) -ENDIF(HAVE_LIBLTDL) -IF(NOT HAVE_DIRNAME) - SET(playercore_srcs ${playercore_srcs} ../replace/dirname.c) -ENDIF(NOT HAVE_DIRNAME) +ENDIF (HAVE_LIBLTDL) +IF (NOT HAVE_DIRNAME) + SET (playercoreSrcs ${playercoreSrcs} ${PROJECT_SOURCE_DIR}/replace/dirname.c) +ENDIF (NOT HAVE_DIRNAME) -PLAYER_ADD_LIBRARY (playercore ${playercore_srcs} ${player_interfaces_h} ${playerxdr_h}) +PLAYER_ADD_LIBRARY (playercore ${playercoreSrcs} ${player_interfaces_h} ${playerxdr_h}) +TARGET_LINK_LIBRARIES (playercore ${coreLibs}) +PLAYER_MAKE_PKGCONFIG ("playercore" "Player core library - part of the Player Project" + "playererror" "" "" "${corePCLibs}") -TARGET_LINK_LIBRARIES(playercore ${CORELIBS}) -PLAYER_MAKE_PKGCONFIG ("playercore" "Player core library - part of the Player Project" "playererror" "" "" "${CORE_PC_LIBS}") +SET (playererrorSrcs error.c) +PLAYER_ADD_LIBRARY (playererror ${playererrorSrcs}) +PLAYER_MAKE_PKGCONFIG ("playererror" "Player error reporting library - part of the Player Project" + "" "" "" "") -SET (playererror_srcs error.c) -PLAYER_ADD_LIBRARY (playererror ${playererror_srcs}) -PLAYER_MAKE_PKGCONFIG ("playererror" "Player error reporting library - part of the Player Project" "" "" "" "") - -SET (playerutils_srcs interface_util.c - addr_util.c) -PLAYER_ADD_LIBRARY (playerutils ${playerutils_srcs} ${interface_table_h}) +SET (playerutilsSrcs interface_util.c + addr_util.c) +PLAYER_ADD_LIBRARY (playerutils ${playerutilsSrcs} ${interface_table_h}) TARGET_LINK_LIBRARIES (playerutils playererror) -PLAYER_MAKE_PKGCONFIG ("playerutils" "Player utilities library - part of the Player Project" "" "" "" "") +PLAYER_MAKE_PKGCONFIG ("playerutils" "Player utilities library - part of the Player Project" + "" "" "" "") PLAYER_INSTALL_HEADERS (playercore addr_util.h configfile.h Modified: code/player/trunk/libplayertcp/CMakeLists.txt =================================================================== --- code/player/trunk/libplayertcp/CMakeLists.txt 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/libplayertcp/CMakeLists.txt 2008-06-17 01:23:36 UTC (rev 6607) @@ -7,12 +7,12 @@ OPTION (ENABLE_TCP_NODELAY "Turn off Nagel's buffering algorithm (which may increase socket latency when used)" OFF) SET (playertcpSrcs socket_util.c playertcp.cc remote_driver.cc) - IF(NOT HAVE_POLL) - SET(playertcpSrcs ${playertcpSrcs} ../replace/poll.c) - ENDIF(NOT HAVE_POLL) - IF(NOT HAVE_COMPRESSBOUND) - SET(playertcpSrcs ${playertcpSrcs} ../replace/compressBound.c) - ENDIF(NOT HAVE_COMPRESSBOUND) + IF (NOT HAVE_POLL) + SET (playertcpSrcs ${playertcpSrcs} ${PROJECT_SOURCE_DIR}/replace/poll.c) + ENDIF (NOT HAVE_POLL) + IF (NOT HAVE_COMPRESSBOUND) + SET (playertcpSrcs ${playertcpSrcs} ${PROJECT_SOURCE_DIR}/replace/compressBound.c) + ENDIF (NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playertcp ${playertcpSrcs}) TARGET_LINK_LIBRARIES (playertcp playercore playererror playerutils playerxdr) IF (HAVE_Z) @@ -26,12 +26,12 @@ IF (INCLUDE_UDP) SET (playerudpSrcs playerudp.cc) - IF(NOT HAVE_POLL) - SET(playerudpSrcs ${playerudpSrcs} ../replace/poll.c) - ENDIF(NOT HAVE_POLL) - IF(NOT HAVE_COMPRESSBOUND) - SET(playerudpSrcs ${playerudpSrcs} ../replace/compressBound.c) - ENDIF(NOT HAVE_COMPRESSBOUND) + IF (NOT HAVE_POLL) + SET(playerudpSrcs ${playerudpSrcs} ${PROJECT_SOURCE_DIR}/replace/poll.c) + ENDIF (NOT HAVE_POLL) + IF (NOT HAVE_COMPRESSBOUND) + SET (playerudpSrcs ${playerudpSrcs} ${PROJECT_SOURCE_DIR}/replace/compressBound.c) + ENDIF (NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playerudp ${playerudpSrcs}) TARGET_LINK_LIBRARIES (playerudp playercore playererror playerutils playerxdr) TARGET_LINK_LIBRARIES (playerudp z) Modified: code/player/trunk/replace/clock_gettime.c =================================================================== --- code/player/trunk/replace/clock_gettime.c 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/replace/clock_gettime.c 2008-06-17 01:23:36 UTC (rev 6607) @@ -20,9 +20,6 @@ * */ -#include <playerconfig.h> - - #include <sys/time.h> /* This replacement function originally written by Klass Gadeyne Modified: code/player/trunk/server/libplayerdrivers/CMakeLists.txt =================================================================== --- code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-06-17 01:23:36 UTC (rev 6607) @@ -37,12 +37,12 @@ LIST (APPEND allSourceNames ${PLAYER_BUILT_DRIVEREXTRAS}) ENDIF (PLAYER_BUILT_DRIVEREXTRAS) MAP_TO_LIST (driversSrcs "${allSourceNames}" PLAYER_DRIVERSLIB_SOURCES_MAP) -IF(NOT HAVE_CFMAKERAW) - LIST(APPEND driversSrcs ../../replace/cfmakeraw.c) -ENDIF(NOT HAVE_CFMAKERAW) -IF(NOT HAVE_ROUND) - LIST(APPEND driversSrcs ../../replace/round.c) -ENDIF(NOT HAVE_ROUND) +IF (NOT HAVE_CFMAKERAW) + LIST (APPEND driversSrcs ${PROJECT_SOURCE_DIR}/replace/cfmakeraw.c) +ENDIF (NOT HAVE_CFMAKERAW) +IF (NOT HAVE_ROUND) + LIST (APPEND driversSrcs ${PROJECT_SOURCE_DIR}/replace/round.c) +ENDIF (NOT HAVE_ROUND) FILTER_DUPLICATES (driversSrcs "${driversSrcs}") # MESSAGE (STATUS "Sources is ${driversSrcs}") Modified: code/player/trunk/utils/pmap/CMakeLists.txt =================================================================== --- code/player/trunk/utils/pmap/CMakeLists.txt 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/CMakeLists.txt 2008-06-17 01:23:36 UTC (rev 6607) @@ -10,19 +10,36 @@ LIST_TO_STRING (GSL_CFLAGS "${GSL_PKG_CFLAGS}") LIST_TO_STRING (GSL_LDFLAGS "${GSL_PKG_LDFLAGS}") - SET (pmapSrcs logfile.cpp omap.cpp pmap.cpp rmap.cpp slap.cpp) - SET (lodoSrcs lodo.cpp slap.cpp) - SET (pmaptestSrcs pmap_test.cpp) + INCLUDE (FindOpenGL) + INCLUDE (FindGLUT) + + SET (pmapconfig_h_in "${CMAKE_CURRENT_SOURCE_DIR}/pmapconfig.h.in") + SET (pmapconfig_h "${CMAKE_CURRENT_BINARY_DIR}/pmapconfig.h") + CONFIGURE_FILE (${pmapconfig_h_in} ${pmapconfig_h}) + + SET (pmapSrcs logfile.cpp omap.cpp pmap.cpp rmap.cpp slap.cpp ${pmapconfig_h}) + SET (lodoSrcs lodo.cpp slap.cpp ${pmapconfig_h}) + SET (pmaptestSrcs pmap_test.cpp ${pmapconfig_h}) SET (lododriverSrcs lodo_driver.cc) - INCLUDE_DIRECTORIES (${PROJECT_SOURCE_DIR}/client_libs) + INCLUDE_DIRECTORIES (${PROJECT_SOURCE_DIR}/client_libs + ${CMAKE_CURRENT_BINARY_DIR}) + IF (GLUT_FOUND) + INCLUDE_DIRECTORIES (${GLUT_INCLUDE_DIR}) + ENDIF (GLUT_FOUND) PLAYER_ADD_EXECUTABLE (pmaptest ${pmaptestSrcs}) TARGET_LINK_LIBRARIES (pmaptest pmap lodo) + IF (GLUT_FOUND) + TARGET_LINK_LIBRARIES (pmaptest ${GLUT_LIBRARIES}) + ENDIF (GLUT_FOUND) SET_TARGET_PROPERTIES (pmaptest PROPERTIES LINK_FLAGS "${GSL_LDFLAGS}") PLAYER_ADD_LIBRARY (pmap ${pmapSrcs}) + IF (GLUT_FOUND) + TARGET_LINK_LIBRARIES (pmap ${GLUT_LIBRARIES}) + ENDIF (GLUT_FOUND) SET_SOURCE_FILES_PROPERTIES (${pmapSrcs} PROPERTIES COMPILE_FLAGS "${GSL_CFLAGS} --fast-math") SET_TARGET_PROPERTIES (pmap PROPERTIES @@ -30,6 +47,9 @@ PLAYER_ADD_LIBRARY (lodo ${lodoSrcs}) TARGET_LINK_LIBRARIES (lodo playercore) + IF (GLUT_FOUND) + TARGET_LINK_LIBRARIES (lodo ${GLUT_LIBRARIES}) + ENDIF (GLUT_FOUND) SET_SOURCE_FILES_PROPERTIES (${lodoSrcs} PROPERTIES COMPILE_FLAGS "${GSL_CFLAGS} --fast-math") SET_TARGET_PROPERTIES (lodo PROPERTIES @@ -37,6 +57,9 @@ PLAYER_ADD_LIBRARY (lododriver ${lododriverSrcs}) TARGET_LINK_LIBRARIES (lododriver lodo) + IF (GLUT_FOUND) + TARGET_LINK_LIBRARIES (lododriver ${GLUT_LIBRARIES}) + ENDIF (GLUT_FOUND) ELSE (GSL_PKG_FOUND) MESSAGE (STATUS "pmap utilities will not be built - GSL not found") ENDIF (GSL_PKG_FOUND) Modified: code/player/trunk/utils/pmap/lodo.cpp =================================================================== --- code/player/trunk/utils/pmap/lodo.cpp 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/lodo.cpp 2008-06-17 01:23:36 UTC (rev 6607) @@ -24,7 +24,7 @@ CVS: $Id$ */ -#include "config.h" +#include "pmapconfig.h" #include <assert.h> #include <math.h> @@ -37,7 +37,7 @@ #include "lodo.h" -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND #include <GL/glut.h> #endif @@ -676,7 +676,7 @@ // Draw a scan void lodo_draw_scan(lodo_t *self, lodo_scan_t *scan) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i; vector2_t p; @@ -713,7 +713,7 @@ // Draw current map (hits) void lodo_draw_map(lodo_t *self) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i; vector3_t p; Modified: code/player/trunk/utils/pmap/omap.cpp =================================================================== --- code/player/trunk/utils/pmap/omap.cpp 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/omap.cpp 2008-06-17 01:23:36 UTC (rev 6607) @@ -24,7 +24,7 @@ */ -#include "config.h" +#include "pmapconfig.h" #include <assert.h> #include <errno.h> @@ -33,7 +33,7 @@ #include <stdio.h> #include <string.h> -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND #include <GL/glut.h> #endif @@ -205,7 +205,7 @@ // Draw the current map void omap_draw_map(omap_t *self, double scale) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i, j; // Set pixel zoom factor so DrawPixel ops align Modified: code/player/trunk/utils/pmap/pmap.cpp =================================================================== --- code/player/trunk/utils/pmap/pmap.cpp 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/pmap.cpp 2008-06-17 01:23:36 UTC (rev 6607) @@ -22,7 +22,7 @@ Date: 19 Nov 2004 CVS: $Id$ */ -#include "config.h" +#include "pmapconfig.h" #include <assert.h> #include <math.h> @@ -32,7 +32,7 @@ #include <string.h> #include <gsl/gsl_randist.h> -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND #include <GL/glut.h> #endif @@ -574,7 +574,7 @@ // Draw the current range scan void pmap_draw_scan(pmap_t *self, double *ranges) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i, best_i; double max_w; vector2_t p; @@ -634,7 +634,7 @@ // Draw all samples void pmap_draw_samples(pmap_t *self) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i; pmap_sample_t *sample; @@ -658,7 +658,7 @@ // Draw a particular sample void pmap_draw_sample(pmap_t *self, int sample_index) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i; pmap_sample_t *sample; pose2_t pose; @@ -683,7 +683,7 @@ // Draw a candidate map void pmap_draw_map(pmap_t *self, double scale) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND pmap_draw_sample_map(self, scale, self->best_sample); return; #endif @@ -693,7 +693,7 @@ // Draw a particular sample map void pmap_draw_sample_map(pmap_t *self, double scale, int sample_index) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i, j; pmap_sample_t *sample; Modified: code/player/trunk/utils/pmap/pmap_test.cpp =================================================================== --- code/player/trunk/utils/pmap/pmap_test.cpp 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/pmap_test.cpp 2008-06-17 01:23:36 UTC (rev 6607) @@ -144,7 +144,7 @@ @endverbatim */ -#include "config.h" +#include "pmapconfig.h" #include <assert.h> #include <math.h> @@ -156,7 +156,7 @@ #include <unistd.h> #include <sys/time.h> -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND #include <GL/glut.h> #endif @@ -277,7 +277,7 @@ // Key callback void win_key(unsigned char key, int x, int y) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND // Show the samples if (key == 'T' || key == 't') { @@ -339,7 +339,7 @@ // Mouse callback void win_mouse(int button, int state, int x, int y) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND if (state == GLUT_DOWN) { @@ -360,7 +360,7 @@ // Handle window reshape events void win_reshape(int width, int height) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND glViewport(0, 0, width, height); viewport_width = width; @@ -373,7 +373,7 @@ // Redraw the window void win_redraw() { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND double left, right, top, bot; @@ -440,7 +440,7 @@ if (!gui_pause) { process(); - #ifdef HAVE_LIBGLUT + #ifdef GLUT_FOUND glutPostRedisplay(); #endif } @@ -454,7 +454,7 @@ // Run the GUI int win_run(int *argc, char **argv) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND glutInit(argc, argv); Modified: code/player/trunk/utils/pmap/rmap.cpp =================================================================== --- code/player/trunk/utils/pmap/rmap.cpp 2008-06-17 01:09:01 UTC (rev 6606) +++ code/player/trunk/utils/pmap/rmap.cpp 2008-06-17 01:23:36 UTC (rev 6607) @@ -31,9 +31,9 @@ #include <gsl/gsl_multimin.h> -#include <config.h> +#include "pmapconfig.h" -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND #include <GL/glut.h> #endif @@ -572,7 +572,7 @@ // Draw the current map void rmap_draw_map(rmap_t *self) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i, j; rmap_scan_t *scan; vector2_t p; @@ -609,7 +609,7 @@ // Draw constraints void rmap_draw_cons(rmap_t *self) { -#ifdef HAVE_LIBGLUT +#ifdef GLUT_FOUND int i; rmap_constraint_t *con; vector2_t pa, pb; This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
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. |
From: <ge...@us...> - 2008-06-17 13:54:07
|
Revision: 6629 http://playerstage.svn.sourceforge.net/playerstage/?rev=6629&view=rev Author: gerkey Date: 2008-06-17 13:54:06 -0700 (Tue, 17 Jun 2008) Log Message: ----------- turned off RTKGUI by default, fixed amcl to link against rtk if it's included; fixed location of Boost using CMake 2.6 Modified Paths: -------------- code/player/trunk/client_libs/libplayerc++/CMakeLists.txt code/player/trunk/cmake/internal/GeneralCompileOptions.cmake code/player/trunk/server/drivers/localization/amcl/CMakeLists.txt Modified: code/player/trunk/client_libs/libplayerc++/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-06-17 20:41:40 UTC (rev 6628) +++ code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-06-17 20:54:06 UTC (rev 6629) @@ -5,8 +5,50 @@ IF (BUILD_PLAYERCC) # Look for Boost libraries IF (BUILD_PLAYERCC_BOOST) - IF (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 4) - # There is a new, much better, FindBoost.cmake in 2.6 (see below) + # There is a new, much better, FindBoost.cmake in 2.6 + IF (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 6) + OPTION (Boost_USE_STATIC_LIBS "Use the static versions of the Boost libraries" OFF) + OPTION (USE_BOOST_THREAD "Use the Boost threading library" ON) + MARK_AS_ADVANCED (USE_BOOST_THREAD) + OPTION (USE_BOOST_SIGNALS "Use the Boost signalling library" ON) + MARK_AS_ADVANCED (USE_BOOST_SIGNALS) + + IF (USE_BOOST_THREAD) + SET (BOOST_COMPONENTS thread) + ENDIF (USE_BOOST_THREAD) + IF (USE_BOOST_SIGNALS) + SET (BOOST_COMPONENTS ${BOOST_COMPONENTS} signals) + ENDIF (USE_BOOST_SIGNALS) + FIND_PACKAGE (Boost COMPONENTS ${BOOST_COMPONENTS}) + IF (Boost_FOUND) + INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIR}) + LINK_DIRECTORIES (${Boost_LIBRARY_DIRS}) + + IF (Boost_THREAD_FOUND) + #SET (boostThreadLib -lboost_thread) + #PLAYERCC_ADD_LINK_LIB (boost_thread) + MESSAGE (STATUS + "PlayerC++ client library will be built with Boost::Thread support.") + ELSE (Boost_THREAD_FOUND) + MESSAGE (STATUS + "Boost::Thread library not found, support will not be included.") + ENDIF (Boost_THREAD_FOUND) + + IF (Boost_SIGNALS_FOUND) + #SET (boostSignalsLib -lboost_signals) + #PLAYERCC_ADD_LINK_LIB (boost_signals) + MESSAGE (STATUS + "PlayerC++ client library will be built with Boost::Signals support.") + ELSE (Boost_SIGNALS_FOUND) + MESSAGE (STATUS + "Boost::Signals library not found, support will not be included.") + ENDIF (Boost_SIGNALS_FOUND) + ELSE (Boost_FOUND) + MESSAGE (STATUS + "Boost libraries were not found. Boost::Signals and Boost::Thread support + will not be included in PlayerC++.") + ENDIF (Boost_FOUND) + ELSE (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 6) FIND_PACKAGE (Boost) IF (Boost_FOUND) # For 2.4, assume that if boost is found then both signals and threads are present @@ -57,49 +99,7 @@ "Boost libraries were not found. Boost::Signals and Boost::Thread support will not be included in PlayerC++.") ENDIF (Boost_FOUND) - ELSE (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 4) - OPTION (Boost_USE_STATIC_LIBS "Use the static versions of the Boost libraries" OFF) - OPTION (USE_BOOST_THREAD "Use the Boost threading library" ON) - MARK_AS_ADVANCED (USE_BOOST_THREAD) - OPTION (USE_BOOST_SIGNALS "Use the Boost signalling library" ON) - MARK_AS_ADVANCED (USE_BOOST_SIGNALS) - - IF (USE_BOOST_THREAD) - SET (BOOST_COMPONENTS thread) - ENDIF (USE_BOOST_THREAD) - IF (USE_BOOST_SIGNALS) - SET (BOOST_COMPONENTS ${BOOST_COMPONENTS} signals) - ENDIF (USE_BOOST_SIGNALS) - FIND_PACKAGE (Boost COMPONENTS ${BOOST_COMPONENTS}) - IF (Boost_FOUND) - INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIR}) - LINK_DIRECTORIES (${Boost_LIBRARY_DIRS}) - - IF (Boost_THREAD_FOUND) - SET (boostThreadLib -lboost_thread) - PLAYERCC_ADD_LINK_LIB (boost_thread) - MESSAGE (STATUS - "PlayerC++ client library will be built with Boost::Thread support.") - ELSE (Boost_THREAD_FOUND) - MESSAGE (STATUS - "Boost::Thread library not found, support will not be included.") - ENDIF (Boost_THREAD_FOUND) - - IF (Boost_SIGNALS_FOUND) - SET (boostSignalsLib -lboost_signals) - PLAYERCC_ADD_LINK_LIB (boost_signals) - MESSAGE (STATUS - "PlayerC++ client library will be built with Boost::Signals support.") - ELSE (Boost_SIGNALS_FOUND) - MESSAGE (STATUS - "Boost::Signals library not found, support will not be included.") - ENDIF (Boost_SIGNALS_FOUND) - ELSE (Boost_FOUND) - MESSAGE (STATUS - "Boost libraries were not found. Boost::Signals and Boost::Thread support - will not be included in PlayerC++.") - ENDIF (Boost_FOUND) - ENDIF (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 4) + ENDIF (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 6) ELSE (BUILD_PLAYERCC_BOOST) MESSAGE (STATUS "Boost support disabled. Boost::Signals and Boost::Thread support will not be @@ -165,7 +165,7 @@ TARGET_LINK_LIBRARIES (playerc++ playerxdr playerutils playerc ${PLAYERCC_EXTRA_LINK_LIBRARIES}) PLAYER_MAKE_PKGCONFIG ("playerc++" "C++ wrapper for libplayerc - part of the Player Project" - "playerxdr playerc" "" "" "-lm ${boostThreadLib} ${boostSignalsLib}") + "playerxdr playerc" "" "" "-lm ${Boost_THREAD_LIBRARY} ${Boost_SIGNALS_LIBRARY}") PLAYER_INSTALL_HEADERS (playerc++ ${playercppconfig_h} clientproxy.h Modified: code/player/trunk/cmake/internal/GeneralCompileOptions.cmake =================================================================== --- code/player/trunk/cmake/internal/GeneralCompileOptions.cmake 2008-06-17 20:41:40 UTC (rev 6628) +++ code/player/trunk/cmake/internal/GeneralCompileOptions.cmake 2008-06-17 20:54:06 UTC (rev 6629) @@ -3,7 +3,7 @@ SET (DEBUG_LEVEL NONE CACHE STRING "Level of debug code to be compiled: none, low, medium or high") IF (WITH_GTK) - OPTION (INCLUDE_RTKGUI "Include the RTK GUI in the server." ON) + OPTION (INCLUDE_RTKGUI "Include the RTK GUI in the server." OFF) ENDIF (WITH_GTK) -OPTION (BUILD_SHARED_LIBS "Build the Player libraries as shared libraries." ON) \ No newline at end of file +OPTION (BUILD_SHARED_LIBS "Build the Player libraries as shared libraries." ON) Modified: code/player/trunk/server/drivers/localization/amcl/CMakeLists.txt =================================================================== --- code/player/trunk/server/drivers/localization/amcl/CMakeLists.txt 2008-06-17 20:41:40 UTC (rev 6628) +++ code/player/trunk/server/drivers/localization/amcl/CMakeLists.txt 2008-06-17 20:54:06 UTC (rev 6629) @@ -22,7 +22,7 @@ map/map_draw.c) IF (INCLUDE_RTKGUI) - SET (linkFlags "${GTK_LINKFLAGS}") + SET (linkFlags "-L${PROJECT_BINARY_DIR}/rtk2 -lrtk ${GTK_LINKFLAGS}") SET (cFlags "-I${PROJECT_SOURCE_DIR}/rtk2 ${GTK_CFLAGS}") ELSE (INCLUDE_RTKGUI) SET (linkFlags) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-06-17 18:29:40
|
Revision: 6634 http://playerstage.svn.sourceforge.net/playerstage/?rev=6634&view=rev Author: gbiggs Date: 2008-06-17 18:29:43 -0700 (Tue, 17 Jun 2008) Log Message: ----------- Fixed boost checks under cmake 2.4, made more flexible under 2.6 Modified Paths: -------------- code/player/trunk/client_libs/libplayerc++/CMakeLists.txt code/player/trunk/cmake/pkgconfig.cmake Modified: code/player/trunk/client_libs/libplayerc++/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-06-17 23:03:49 UTC (rev 6633) +++ code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-06-18 01:29:43 UTC (rev 6634) @@ -8,6 +8,7 @@ # There is a new, much better, FindBoost.cmake in 2.6 IF (CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 6) OPTION (Boost_USE_STATIC_LIBS "Use the static versions of the Boost libraries" OFF) + MARK_AS_ADVANCED (Boost_USE_STATIC_LIBS) OPTION (USE_BOOST_THREAD "Use the Boost threading library" ON) MARK_AS_ADVANCED (USE_BOOST_THREAD) OPTION (USE_BOOST_SIGNALS "Use the Boost signalling library" ON) @@ -25,8 +26,11 @@ LINK_DIRECTORIES (${Boost_LIBRARY_DIRS}) IF (Boost_THREAD_FOUND) - #SET (boostThreadLib -lboost_thread) - #PLAYERCC_ADD_LINK_LIB (boost_thread) + GET_FILENAME_COMPONENT (boostThreadLib ${Boost_THREAD_LIBRARY} NAME_WE CACHE) + # Chop off the lib at the front, too, if present + STRING (REGEX REPLACE "^lib" "" boostThreadLib ${boostThreadLib}) + PLAYERCC_ADD_LINK_LIB (${boostThreadLib}) + SET (boostIncludeDir ${Boost_INCLUDE_DIR}) MESSAGE (STATUS "PlayerC++ client library will be built with Boost::Thread support.") ELSE (Boost_THREAD_FOUND) @@ -35,8 +39,10 @@ ENDIF (Boost_THREAD_FOUND) IF (Boost_SIGNALS_FOUND) - #SET (boostSignalsLib -lboost_signals) - #PLAYERCC_ADD_LINK_LIB (boost_signals) + GET_FILENAME_COMPONENT (boostSignalsLib ${Boost_SIGNALS_LIBRARY} NAME_WE CACHE) + STRING (REGEX REPLACE "^lib" "" boostSignalsLib ${boostSignalsLib}) + PLAYERCC_ADD_LINK_LIB (${boostSignalsLib}) + SET (boostIncludeDir ${Boost_INCLUDE_DIR}) MESSAGE (STATUS "PlayerC++ client library will be built with Boost::Signals support.") ELSE (Boost_SIGNALS_FOUND) @@ -62,7 +68,8 @@ PLAYERCC_ADD_LINK_LIB (boost_thread) INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIRS}) LINK_DIRECTORIES (${Boost_LIBRARY_DIRS}) - SET (boostThreadLib -lboost_thread) + SET (boostThreadLib boost_thread) + SET (boostIncludeDir ${Boost_INCLUDE_DIRS}) ELSE (USE_BOOST_THREAD) MESSAGE (STATUS "PlayerC++ client library Boost::Thread support disabled by user.") @@ -83,7 +90,8 @@ PLAYERCC_ADD_LINK_LIB (boost_signals) INCLUDE_DIRECTORIES (${Boost_INCLUDE_DIRS}) LINK_DIRECTORIES (${Boost_LIBRARY_DIRS}) - SET (boostSignalsLib -lboost_signals) + SET (boostSignalsLib boost_signals) + SET (boostIncludeDir ${Boost_INCLUDE_DIRS}) ELSE (USE_BOOST_SIGNALS) MESSAGE (STATUS "PlayerC++ client library Boost::Signals support disabled by @@ -165,7 +173,8 @@ TARGET_LINK_LIBRARIES (playerc++ playerxdr playerutils playerc ${PLAYERCC_EXTRA_LINK_LIBRARIES}) PLAYER_MAKE_PKGCONFIG ("playerc++" "C++ wrapper for libplayerc - part of the Player Project" - "playerxdr playerc" "" "" "-lm ${Boost_THREAD_LIBRARY} ${Boost_SIGNALS_LIBRARY}") + "playerxdr playerc" "" "-I${boostIncludeDir}" + "-lm -L${Boost_LIBRARY_DIRS} -l${boostThreadLib} -l${boostSignalsLib}") PLAYER_INSTALL_HEADERS (playerc++ ${playercppconfig_h} clientproxy.h Modified: code/player/trunk/cmake/pkgconfig.cmake =================================================================== --- code/player/trunk/cmake/pkgconfig.cmake 2008-06-17 23:03:49 UTC (rev 6633) +++ code/player/trunk/cmake/pkgconfig.cmake 2008-06-18 01:29:43 UTC (rev 6634) @@ -8,5 +8,5 @@ Description: @PKG_DESC@ Version: @PLAYER_VERSION@ Requires: @PKG_EXTERNAL_DEPS@ -Libs: -L${libdir} @PKG_LIBFLAGS@ -l@PKG_NAME@ @PKG_INTERNAL_DEPS@ +Libs: -L${libdir} -l@PKG_NAME@ @PKG_LIBFLAGS@ @PKG_INTERNAL_DEPS@ Cflags: -I${includedir}/player-@PLAYER_MAJOR_VERSION@.@PLAYER_MINOR_VERSION@ @PKG_CFLAGS@ \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-06-19 20:14:07
|
Revision: 6648 http://playerstage.svn.sourceforge.net/playerstage/?rev=6648&view=rev Author: gbiggs Date: 2008-06-19 20:14:13 -0700 (Thu, 19 Jun 2008) Log Message: ----------- Replaced urg_nz driver with a new one that uses the new Gearbox urg_nz library Modified Paths: -------------- code/player/trunk/config/CMakeLists.txt code/player/trunk/server/drivers/ranger/urg_nz.cc Added Paths: ----------- code/player/trunk/config/urg_nz.cfg Modified: code/player/trunk/config/CMakeLists.txt =================================================================== --- code/player/trunk/config/CMakeLists.txt 2008-06-19 21:49:14 UTC (rev 6647) +++ code/player/trunk/config/CMakeLists.txt 2008-06-20 03:14:13 UTC (rev 6648) @@ -29,6 +29,7 @@ umass_ATRVJr.cfg umass_ATRVMini.cfg umass_reb.cfg + urg_nz.cfg urglaser.cfg vfh.cfg wavefront.cfg Added: code/player/trunk/config/urg_nz.cfg =================================================================== --- code/player/trunk/config/urg_nz.cfg (rev 0) +++ code/player/trunk/config/urg_nz.cfg 2008-06-20 03:14:13 UTC (rev 6648) @@ -0,0 +1,6 @@ +driver +( + name "urg_nz" + provides ["ranger:0"] + portopts "type=serial,device=/dev/ttyACM0,timeout=1" +) Modified: code/player/trunk/server/drivers/ranger/urg_nz.cc =================================================================== --- code/player/trunk/server/drivers/ranger/urg_nz.cc 2008-06-19 21:49:14 UTC (rev 6647) +++ code/player/trunk/server/drivers/ranger/urg_nz.cc 2008-06-20 03:14:13 UTC (rev 6648) @@ -1,72 +1,60 @@ /* * Player - One Hell of a Robot Server - * Copyright (C) 2003 - * Brian Gerkey + * Copyright (C) 2008 + * Geoffrey Biggs * * - * This program is free software; you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation; either version 2 of the License, or - * (at your option) any later version. + * This program is free software: you can redistribute it and/or modify it under the terms of the + * GNU Lesser General Public License as published by the Free Software Foundation, either version + * 3 of the License, or (at your option) any later version. * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program; if not, write to the Free Software - * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA - * + * This program is distributed in the hope that it will be useful, but WITHOUT ANY WARRANTY; without + * even the implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + * Lesser General Public License for more details. + * + * You should have received a copy of the GNU Lesser General Public License along with this program. + * If not, see <http://www.gnu.org/licenses/>. */ -/////////////////////////////////////////////////////////////////////////// -// -// Desc: Driver wrapper around the Gearbox urg_nz library. -// Author: Geoffrey Biggs -// Date: 25/02/2008 -// -// Provides - Ranger device. -// -/////////////////////////////////////////////////////////////////////////// +/* + Desc: Wrapper driver around the Gearbox urg_nz library (see http://gearbox.sourceforge.net) + Author: Geoffrey Biggs + Date: 20 June 2008 + CVS: $Id$ +*/ /** @ingroup drivers */ /** @{ */ /** @defgroup driver_urg_nz urg_nz * @brief Gearbox urg_nz Hokuyo URG laser scanner driver library -This driver provides a @ref interface_ranger interface to the urg_nz Hokuyo URG laser scanner driver -provided by Gearbox. Communication with the laser can be either via USB or RS232. The driver -supports SCIP procol versions 1 and 2. + This driver provides a @ref interface_ranger interface to the urg_nz Hokuyo URG laser scanner + driver provided by Gearbox. Communication with the laser is via the Gearbox Flexiport library. The + driver supports the SCIP protocol versions 1 and 2. -@par Compile-time dependencies + @par Compile-time dependencies -- Gearbox library urg_nz + - Gearbox library urg_nz + - Gearbox library flexiport -@par Provides + @par Provides -- @ref interface_ranger : Output ranger interface + - @ref interface_ranger : Output ranger interface -@par Configuration requests + @par Configuration requests -- PLAYER_RANGER_REQ_GET_GEOM -- PLAYER_RANGER_REQ_GET_CONFIG -- PLAYER_RANGER_REQ_SET_CONFIG - - Note: Only the min_angle and max_angle values can be configured using this request. + - PLAYER_RANGER_REQ_GET_GEOM + - PLAYER_RANGER_REQ_GET_CONFIG + - PLAYER_RANGER_REQ_SET_CONFIG + - Note: Only the min_angle, max_angle and frequency values can be configured using this request. + In addition, the frequency value must be equivalent to a suitable RPM value (see the urg_nz + library documentation for suitable values). -@par Configuration file options + @par Configuration file options - - port (string) - - Default: "/dev/ttyACM0" - - Port to which the laser is connected. Can be a serial port or the port associated with a USB ACM - device. - - baudrate (integer) - - Default: 115200 - - Initial baud rate to connect at. Can be changed with the "baudrate" property. Valid rates are - 19200, 57600 and 115200. Only applies when use_serial is true. - - use_serial (boolean) - - Default: false - - Connect over an RS232 serial connection instead of the default USB connection. + - portopts (string) + - Default: "type=serial,device=/dev/ttyACM0,timeout=1" + - Options to create the Flexiport port with. - pose (float 6-tuple: (m, m, m, rad, rad, rad)) - Default: [0.0 0.0 0.0 0.0 0.0 0.0] - Pose (x, y, z, roll, pitch, yaw) of the laser relative to its parent object (e.g. the robot). @@ -74,348 +62,383 @@ - Default: [0.0 0.0 0.0] - Size of the laser in metres. - min_angle (float, radians) - - Default: -2.094 rad (-120.0 degrees) - - Minimum scan angle to return. + - Default: -2.08 rad (-119.0 degrees) + - Minimum scan angle to return. Will be adjusted if outside the laser's scannable range. - max_angle (float, radians) - - Default: 2.094 rad (120.0 degrees) - - Maximum scan angle to return. + - Default: 2.08 rad (119.0 degrees) + - Maximum scan angle to return. Will be adjusted if outside the laser's scannable range. + - frequency (float, Hz) + - Default: 10Hz + - The frequency at which the laser operates. This must be equivalent to a suitable RPM value. See + - the urg_nz library documentation for suitable values. + - power (boolean) + - Default: true + - If true, the sensor power will be switched on upon driver activation (i.e. when the first + client connects). Otherwise a power request must be made to turn it on before data will be + received. - verbose (boolean) - Default: false - Enable verbose debugging information in the underlying library. -@par Properties + @par Properties - baudrate (integer) - - Change the baud rate of the connection to the laser. Valid rates are 19200, 57600 and 115200. - Only applies when use_serial is true. Not currently supported if SCIP v2 is in use. + - Default: 19200bps + - Change the baud rate of the connection to the laser. See urg_nz documentation for valid values. -@par Example + @par Example -@verbatim -driver -( - name "urg_nz" - provides ["ranger:0"] - port "/dev/ttyACM0" -) -@endverbatim + @verbatim + driver + ( + name "urg_nz" + provides ["ranger:0"] + portopts "type=serial,device=/dev/ttyS0,timeout=1" + ) + @endverbatim -@author Geoffrey Biggs + @author Geoffrey Biggs -*/ + */ /** @} */ -#include <math.h> -#include <stdio.h> -#include <stdlib.h> -#include <unistd.h> - #include <string> -#include <iostream> -using namespace std; #include <urg_nz/urg_nz.h> - #include <libplayercore/playercore.h> -const int DEFAULT_BAUDRATE = 115200; +const int DEFAULT_BAUDRATE = 19200; +const int DEFAULT_SPEED = 600; +//////////////////////////////////////////////////////////////////////////////////////////////////// +// Driver object +//////////////////////////////////////////////////////////////////////////////////////////////////// + class UrgDriver : public Driver { - public: - UrgDriver (ConfigFile* cf, int section); - ~UrgDriver (void); + public: + UrgDriver (ConfigFile* cf, int section); + ~UrgDriver (void); - virtual int Setup (void); - virtual int Shutdown (void); - virtual int ProcessMessage (QueuePointer &resp_queue, player_msghdr *hdr, void *data); + virtual int Setup (void); + virtual int Shutdown (void); + virtual int ProcessMessage (QueuePointer &resp_queue, player_msghdr *hdr, void *data); - private: - virtual void Main (void); - bool ReadLaser (void); - bool CalculateMinMaxIndices (void); + private: + virtual void Main (void); + bool ReadLaser (void); + bool AllocateDataSpace (void); - // Configuration parameters - bool useSerial, verbose; - double minAngle, maxAngle; - IntProperty baudRate; - string port; - int numSamples; - // Config received from the laser - urg_nz::urg_nz_laser_config_t config; - // Geometry - player_ranger_geom_t geom; - player_pose3d_t sensorPose; - player_bbox3d_t sensorSize; - // Data storage, etc - double *ranges; - urg_nz::urg_nz_laser_readings_t *readings; - unsigned int minIndex, maxIndex; - // The hardware device itself - urg_nz::urg_laser device; + // Configuration parameters + bool _verbose, _powerOnStartup; + int _frequency; + double _minAngle, _maxAngle; + IntProperty _baudRate; + std::string _portOpts; + // Geometry + player_ranger_geom_t geom; + player_pose3d_t sensorPose; + player_bbox3d_t sensorSize; + // The hardware device itself + urg_nz::URGLaser _device; + // Data storage + urg_nz::URGData _data; + double *_ranges; }; -Driver* -UrgDriver_Init (ConfigFile* cf, int section) -{ - return reinterpret_cast <Driver*> (new UrgDriver (cf, section)); -} +//////////////////////////////////////////////////////////////////////////////////////////////////// +// Constructor/destructor +//////////////////////////////////////////////////////////////////////////////////////////////////// -void urg_nz_Register(DriverTable* table) +UrgDriver::UrgDriver (ConfigFile* cf, int section) : + Driver (cf, section, false, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_RANGER_CODE), + _baudRate ("baudrate", DEFAULT_BAUDRATE, false), _ranges (NULL) { - table->AddDriver ("urg_nz", UrgDriver_Init); -} + // Get the baudrate and motor speed + RegisterProperty ("baudrate", &_baudRate, cf, section); -UrgDriver::UrgDriver (ConfigFile* cf, int section) - : Driver (cf, section, false, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_RANGER_CODE), - baudRate ("baudrate", DEFAULT_BAUDRATE, false), ranges (NULL), readings (NULL), - minIndex (0), maxIndex (urg_nz::MAX_READINGS) -{ - // Get and sanity-check the baudrate - RegisterProperty ("baudrate", &baudRate, cf, section); - if (baudRate.GetValue () != 19200 && baudRate.GetValue () != 57600 && baudRate.GetValue () != 115200) - { - PLAYER_WARN2 ("urg_nz: Ignored bad baud rate: %d, using default of %d", baudRate.GetValue (), DEFAULT_BAUDRATE); - baudRate.SetValue (DEFAULT_BAUDRATE); - } + // Get config + _minAngle = cf->ReadFloat (section, "min_angle", -2.08); + _maxAngle = cf->ReadFloat (section, "max_angle", 2.08); + _frequency = cf->ReadInt (section, "frequency", 10); + _portOpts = cf->ReadString (section, "portopts", "type=serial,device=/dev/ttyACM0,timeout=1"); + _verbose = cf->ReadBool (section, "verbose", false); + _powerOnStartup = cf->ReadBool (section, "power", true); - // Get config - minAngle = cf->ReadFloat (section, "min_angle", DTOR (-120.0f)); - maxAngle = cf->ReadFloat (section, "max_angle", DTOR (120.0f)); - useSerial = cf->ReadBool (section, "use_serial", false); - port = cf->ReadString (section, "port", "/dev/ttyACM0"); - verbose = cf->ReadBool (section, "verbose", false); + // Set up geometry information + geom.pose.px = cf->ReadTupleLength (section, "pose", 0, 0.0); + geom.pose.py = cf->ReadTupleLength (section, "pose", 1, 0.0); + geom.pose.pz = cf->ReadTupleLength (section, "pose", 2, 0.0); + geom.pose.proll = cf->ReadTupleAngle (section, "pose", 3, 0.0); + geom.pose.ppitch = cf->ReadTupleAngle (section, "pose", 4, 0.0); + geom.pose.pyaw = cf->ReadTupleAngle (section, "pose", 5, 0.0); + geom.size.sw = cf->ReadTupleLength (section, "size", 0, 0.0); + geom.size.sl = cf->ReadTupleLength (section, "size", 1, 0.0); + geom.size.sh = cf->ReadTupleLength (section, "size", 2, 0.0); + geom.sensor_poses_count = 1; + geom.sensor_poses = &sensorPose; + memcpy(geom.sensor_poses, &geom.pose, sizeof (geom.pose)); + geom.sensor_sizes_count = 1; + geom.sensor_sizes = &sensorSize; + memcpy(geom.sensor_sizes, &geom.size, sizeof (geom.size)); - // Set up geometry information - geom.pose.px = cf->ReadTupleLength (section, "pose", 0, 0.0f); - geom.pose.py = cf->ReadTupleLength (section, "pose", 1, 0.0f); - geom.pose.pz = cf->ReadTupleLength (section, "pose", 2, 0.0f); - geom.pose.proll = cf->ReadTupleAngle (section, "pose", 3, 0.0f); - geom.pose.ppitch = cf->ReadTupleAngle (section, "pose", 4, 0.0f); - geom.pose.pyaw = cf->ReadTupleAngle (section, "pose", 5, 0.0f); - geom.size.sw = cf->ReadTupleLength (section, "size", 0, 0.0f); - geom.size.sl = cf->ReadTupleLength (section, "size", 1, 0.0f); - geom.size.sh = cf->ReadTupleLength (section, "size", 2, 0.0f); - geom.sensor_poses_count = 1; - geom.sensor_poses = &sensorPose; - memcpy (geom.sensor_poses, &geom.pose, sizeof (geom.pose)); - geom.sensor_sizes_count = 1; - geom.sensor_sizes = &sensorSize; - memcpy (geom.sensor_sizes, &geom.size, sizeof (geom.size)); - - // Turn on/off verbose mode - device.SetVerbose (verbose); + // Turn on/off verbose mode + _device.SetVerbose (_verbose); } UrgDriver::~UrgDriver (void) { - if (ranges != NULL) - delete[] ranges; - if (readings != NULL) - delete[] readings; + if (_ranges != NULL) + delete[] _ranges; } -int UrgDriver::Setup (void) +//////////////////////////////////////////////////////////////////////////////////////////////////// +// Driver implementation +//////////////////////////////////////////////////////////////////////////////////////////////////// + +bool UrgDriver::AllocateDataSpace (void) { - try - { - // Open the laser - device.Open (port.c_str (), useSerial, baudRate.GetValue ()); - // Get the current config - device.GetSensorConfig (&config); - if (!CalculateMinMaxIndices ()) - return -1; - } - catch (urg_nz::urg_nz_exception &e) - { - PLAYER_ERROR2 ("urg_nz: Failed to setup laser driver: (%d) %s", e.error_code, e.error_desc.c_str ()); - SetError (e.error_code); - return -1; - } + if (_ranges != NULL) + delete _ranges; - // Create space to store data - if ((ranges = new double[maxIndex - minIndex + 1]) == NULL) - { - PLAYER_ERROR ("urg_nz: Failed to allocate data store."); - return -1; - } - if ((readings = new urg_nz::urg_nz_laser_readings_t) == NULL) - { - PLAYER_ERROR ("urg_nz: Failed to allocate intermediate data store."); - return -1; - } + int numRanges = _device.AngleToStep (_maxAngle) - _device.AngleToStep (_minAngle) + 1; + if ((_ranges = new double[numRanges]) == NULL) + { + PLAYER_ERROR1 ("urg_nz: Failed to allocate space for %d range readings.", numRanges); + return false; + } - StartThread(); - return 0; + return true; } -int UrgDriver::Shutdown (void) +void UrgDriver::Main (void) { - StopThread(); + while (true) + { + pthread_testcancel (); + ProcessMessages (); - device.Close (); - - if (ranges != NULL) - { - delete[] ranges; - ranges = NULL; - } - if (readings != NULL) - { - delete readings; - readings = NULL; - } - - return 0; + if (!ReadLaser ()) + break; + } } int UrgDriver::ProcessMessage (QueuePointer &resp_queue, player_msghdr *hdr, void *data) { - // Check for capability requests - HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, PLAYER_MSGTYPE_REQ, PLAYER_CAPABILTIES_REQ); - HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_GEOM); - HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_CONFIG); + // Check for capability requests + HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, + PLAYER_MSGTYPE_REQ, PLAYER_CAPABILTIES_REQ); + HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, + PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_GEOM); + HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, + PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_CONFIG); + HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, + PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_SET_CONFIG); + HANDLE_CAPABILITY_REQUEST (device_addr, resp_queue, hdr, data, + PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_POWER); - // Check for a change in the baud rate property; we need to handle this manually rather than letting the driver - // class handle it because we need to change the baud rate in the library - if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_SET_INTPROP_REQ, this->device_addr)) - { - player_intprop_req_t *req = reinterpret_cast<player_intprop_req_t*> (data); - if (strcmp(req->key, "baudrate") == 0) - { - try - { - // Change the baud rate - if (device.ChangeBaud (baudRate, req->value) == 0) - { - baudRate.SetValueFromMessage (data); - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_SET_INTPROP_REQ, NULL, 0, NULL); - } - else - { - PLAYER_WARN ("urg_nz: Unable to change baud rate."); - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_SET_INTPROP_REQ, NULL, 0, NULL); - } - } - catch (urg_nz::urg_nz_exception &e) - { - PLAYER_ERROR2 ("urg_nz: Fatal error while changing baud rate: (%d) %s", e.error_code, e.error_desc.c_str ()); - SetError (e.error_code); - return -1; - } - return 0; - } - } - // Standard ranger messages - else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_GEOM, device_addr)) - { - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_GEOM, &geom, sizeof (geom), NULL); - return 0; - } - else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_CONFIG, device_addr)) - { - player_ranger_config_t rangerConfig; - rangerConfig.min_angle = minAngle; - rangerConfig.max_angle = maxAngle; - rangerConfig.resolution = config.resolution; - rangerConfig.max_range = config.max_range / 1000.0f; - rangerConfig.range_res = 0.0f; - rangerConfig.frequency = 0.0f; - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_CONFIG, &rangerConfig, sizeof (rangerConfig), NULL); - return 0; - } - else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_SET_CONFIG, device_addr)) - { - player_ranger_config_t *newParams = reinterpret_cast<player_ranger_config_t*> (data); - minAngle = newParams->min_angle; - maxAngle = newParams->max_angle; - if (!CalculateMinMaxIndices ()) - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_RANGER_REQ_GET_CONFIG, NULL, 0, NULL); - else - { - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_CONFIG, newParams, sizeof (*newParams), NULL); - // Reallocate ranges - delete[] ranges; - if ((ranges = new double[maxIndex - minIndex + 1]) == NULL) - { - PLAYER_ERROR ("urg_nz: Failed to allocate data store."); - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_RANGER_REQ_GET_CONFIG, NULL, 0, NULL); - } - else - Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_CONFIG, newParams, sizeof (*newParams), NULL); - } - return 0; - } + // Property handlers that need to be done manually due to calling into the urg_nz library. + if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_SET_INTPROP_REQ, this->device_addr)) + { + player_intprop_req_t *req = reinterpret_cast<player_intprop_req_t*> (data); + // Change in the baud rate + if (strncmp (req->key, "baudrate", 8) == 0) + { + try + { + // Change the baud rate + _device.SetBaud (req->value); + } + catch (urg_nz::URGError &e) + { + if (e.Code () != urg_nz::URG_ERR_NOTSERIAL) + { + PLAYER_ERROR2 ("urg_nz: Error while changing baud rate: (%d) %s", e.Code (), + e.what ()); + SetError (e.Code ()); + } + else + PLAYER_WARN ("urg_nz: Cannot change the baud rate of a non-serial connection."); - return -1; + Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_SET_INTPROP_REQ, + NULL, 0, NULL); + return -1; + } + _baudRate.SetValueFromMessage (data); + Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_SET_INTPROP_REQ, NULL, + 0, NULL); + return 0; + } + } + + // Standard ranger messages + else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_GEOM, + device_addr)) + { + Publish (device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_GEOM, + &geom, sizeof (geom), NULL); + return 0; + } + else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_GET_CONFIG, + device_addr)) + { + player_ranger_config_t rangerConfig; + urg_nz::URGSensorInfo info; + _device.GetSensorInfo (&info); + + rangerConfig.min_angle = _minAngle; // These two are user-configurable + rangerConfig.max_angle = _maxAngle; + rangerConfig.resolution = info.resolution; + rangerConfig.max_range = info.maxRange / 1000.0; + rangerConfig.range_res = 0.001; // 1mm + rangerConfig.frequency = info.speed / 60.0; + Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_CONFIG, + &rangerConfig, sizeof (rangerConfig), NULL); + return 0; + } + else if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, PLAYER_RANGER_REQ_SET_CONFIG, + device_addr)) + { + player_ranger_config_t *newParams = reinterpret_cast<player_ranger_config_t*> (data); + + _minAngle = newParams->min_angle; + _maxAngle = newParams->max_angle; + if (!AllocateDataSpace ()) + { + Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_RANGER_REQ_GET_CONFIG, + NULL, 0, NULL); + return -1; + } + + _frequency = static_cast<int> (newParams->frequency); + try + { + urg_nz::URGSensorInfo info; + _device.GetSensorInfo (&info); + if (_minAngle < info.minAngle) + { + _minAngle = info.minAngle; + PLAYER_WARN1 ("urg_nz: Adjusted min_angle to %lf", _minAngle); + } + if (_maxAngle> info.maxAngle) + { + _maxAngle = info.maxAngle; + PLAYER_WARN1 ("urg_nz: Adjusted max_angle to %lf", _maxAngle); + } + _device.SetMotorSpeed (_frequency * 60); + } + catch (urg_nz::URGError &e) + { + PLAYER_ERROR2 ("urg_nz: Library error while changing settings: (%d) %s", e.Code (), + e.what ()); + SetError (e.Code ()); + Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_NACK, PLAYER_RANGER_REQ_GET_CONFIG, + NULL, 0, NULL); + return -1; + } + + Publish(device_addr, resp_queue, PLAYER_MSGTYPE_RESP_ACK, PLAYER_RANGER_REQ_GET_CONFIG, + newParams, sizeof (*newParams), NULL); + return 0; + } + + return -1; } -void UrgDriver::Main (void) +bool UrgDriver::ReadLaser (void) { - while (true) - { - pthread_testcancel (); - ProcessMessages (); + player_ranger_data_range_t rangeData; - if (!ReadLaser ()) - break; - } + try + { + unsigned int numRead = _device.GetRanges (&_data, _minAngle, _maxAngle); + } + catch (urg_nz::URGError &e) + { + PLAYER_ERROR2 ("urg_nz: Failed to read scan: (%d) %s", e.Code (), e.what ()); + SetError (e.Code ()); + return false; + } + + for (unsigned int ii = 0; ii < _data.Length (); ii++) + _ranges[ii] = _data[ii] / 1000.0f; + rangeData.ranges = _ranges; + rangeData.ranges_count = _data.Length (); + Publish (device_addr, PLAYER_MSGTYPE_DATA, PLAYER_RANGER_DATA_RANGE, + reinterpret_cast<void*> (&rangeData), sizeof (rangeData), NULL); + + return true; } -bool UrgDriver::ReadLaser (void) +int UrgDriver::Setup (void) { - player_ranger_data_range_t rangeData; + try + { + // Open the laser + _device.Open (_portOpts); + // Get the sensor information and check _minAngle and _maxAngle are OK + urg_nz::URGSensorInfo info; + _device.GetSensorInfo (&info); + if (_minAngle < info.minAngle) + { + _minAngle = info.minAngle; + PLAYER_WARN1 ("urg_nz: Adjusted min_angle to %lf", _minAngle); + } + if (_maxAngle> info.maxAngle) + { + _maxAngle = info.maxAngle; + PLAYER_WARN1 ("urg_nz: Adjusted max_angle to %lf", _maxAngle); + } + if (!AllocateDataSpace ()) + return -1; - try - { - unsigned int numRead = device.GetReadings (readings, minIndex, maxIndex); - if (numRead != (maxIndex - minIndex + 1)) - { - PLAYER_WARN2 ("urg_nz: Warning: Got an unexpected number of range readings (%d != %d)", numRead, maxIndex - minIndex + 1); - return true; // Maybe we'll get more next time - } + if (_powerOnStartup) + _device.SetPower (true); - for (unsigned int ii; ii < numRead; ii++) - ranges[ii] = readings->Readings[ii] / 1000.0f; - rangeData.ranges = ranges; - rangeData.ranges_count = numRead; - Publish (device_addr, PLAYER_MSGTYPE_DATA, PLAYER_RANGER_DATA_RANGE, reinterpret_cast<void*> (&rangeData), sizeof (rangeData), NULL); - } - catch (urg_nz::urg_nz_exception &e) - { - PLAYER_ERROR2 ("urg_nz: Failed to read scan: (%d) %s", e.error_code, e.error_desc.c_str ()); - SetError (e.error_code); - return false; - } + try + { + _device.SetBaud (_baudRate.GetValue ()); + } + catch (urg_nz::URGError &e) + { + if (e.Code () != urg_nz::URG_ERR_NOTSERIAL) + throw; + PLAYER_WARN ("urg_nz: Cannot change the baud rate of a non-serial connection."); + } + } + catch (urg_nz::URGError &e) + { + PLAYER_ERROR2 ("urg_nz: Failed to setup laser driver: (%d) %s", e.Code (), e.what ()); + SetError (e.Code ()); + return -1; + } - return true; + StartThread (); + return 0; } -bool UrgDriver::CalculateMinMaxIndices (void) +int UrgDriver::Shutdown (void) { - unsigned int minPossibleIndex, maxPossibleIndex; + StopThread (); - // Calculate min and max scan indices - minIndex = static_cast<unsigned int> (round ((urg_nz::MAX_READINGS / 2) + minAngle / config.resolution)); - maxIndex = static_cast<unsigned int> (round ((urg_nz::MAX_READINGS / 2) + maxAngle / config.resolution)); - // Sanity check - if (minIndex > maxIndex) - minIndex = maxIndex; - // Clip the min and max scan indices - minPossibleIndex = static_cast<unsigned int> (round ((urg_nz::MAX_READINGS / 2) + config.min_angle / config.resolution)); - maxPossibleIndex = static_cast<unsigned int> (round ((urg_nz::MAX_READINGS / 2) + config.max_angle / config.resolution)); - if (minIndex < minPossibleIndex) - { - minIndex = minPossibleIndex; - minAngle = config.min_angle; - PLAYER_WARN1 ("urg_nz: Warning: min_angle clipped to %f", config.min_angle); - } - if (maxIndex > maxPossibleIndex) - { - maxIndex = maxPossibleIndex; - maxAngle = config.max_angle; - PLAYER_WARN1 ("urg_nz: Warning: max_angle clipped to %f", config.max_angle); - } + _device.Close (); + _data.CleanUp (); + if (_ranges != NULL) + delete[] _ranges; - return true; + return 0; } + +//////////////////////////////////////////////////////////////////////////////////////////////////// +// Driver management functions +//////////////////////////////////////////////////////////////////////////////////////////////////// + +Driver* UrgDriver_Init (ConfigFile* cf, int section) +{ + return reinterpret_cast <Driver*> (new UrgDriver (cf, section)); +} + +void urg_nz_Register (DriverTable* table) +{ + table->AddDriver ("urg_nz", UrgDriver_Init); +} This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-06-19 23:59:21
|
Revision: 6652 http://playerstage.svn.sourceforge.net/playerstage/?rev=6652&view=rev Author: gbiggs Date: 2008-06-19 23:59:29 -0700 (Thu, 19 Jun 2008) Log Message: ----------- Fixed some warnings. Modified Paths: -------------- code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c code/player/trunk/server/drivers/ranger/gbxsickacfr.cc code/player/trunk/server/drivers/ranger/urg_nz.cc Modified: code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c =================================================================== --- code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-20 06:42:15 UTC (rev 6651) +++ code/player/trunk/examples/plugins/exampleinterface/eginterf_client.c 2008-06-20 06:59:29 UTC (rev 6652) @@ -86,7 +86,7 @@ player_eginterf_req_t *rep; memset (&rep, 0, sizeof (player_eginterf_req_t)); req.value = blah; - if ((result = playerc_client_request (device->info.client, &device->info, PLAYER_EXAMPLE_REQ_EXAMPLE, &req, &rep)) < 0) + if ((result = playerc_client_request (device->info.client, &device->info, PLAYER_EXAMPLE_REQ_EXAMPLE, &req, (void*) &rep)) < 0) return result; device->value = rep->value; Modified: code/player/trunk/server/drivers/ranger/gbxsickacfr.cc =================================================================== --- code/player/trunk/server/drivers/ranger/gbxsickacfr.cc 2008-06-20 06:42:15 UTC (rev 6651) +++ code/player/trunk/server/drivers/ranger/gbxsickacfr.cc 2008-06-20 06:59:29 UTC (rev 6652) @@ -360,5 +360,8 @@ catch (const std::exception &e) { PLAYER_ERROR1 ("GbxSickAcfr: Failed to read scan: %s\n", e.what ()); + return false; } + + return true; } Modified: code/player/trunk/server/drivers/ranger/urg_nz.cc =================================================================== --- code/player/trunk/server/drivers/ranger/urg_nz.cc 2008-06-20 06:42:15 UTC (rev 6651) +++ code/player/trunk/server/drivers/ranger/urg_nz.cc 2008-06-20 06:59:29 UTC (rev 6652) @@ -352,7 +352,7 @@ try { - unsigned int numRead = _device.GetRanges (&_data, _minAngle, _maxAngle); + _device.GetRanges (&_data, _minAngle, _maxAngle); } catch (urg_nz::URGError &e) { This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-06-24 06:54:33
|
Revision: 6674 http://playerstage.svn.sourceforge.net/playerstage/?rev=6674&view=rev Author: gbiggs Date: 2008-06-24 06:54:42 -0700 (Tue, 24 Jun 2008) Log Message: ----------- Added cvcam driver from Paul Osmialowski Modified Paths: -------------- code/player/trunk/config/CMakeLists.txt code/player/trunk/server/drivers/camera/CMakeLists.txt Added Paths: ----------- code/player/trunk/config/cvcam.cfg code/player/trunk/server/drivers/camera/cvcam/ code/player/trunk/server/drivers/camera/cvcam/CMakeLists.txt code/player/trunk/server/drivers/camera/cvcam/cvcam.cc Modified: code/player/trunk/config/CMakeLists.txt =================================================================== --- code/player/trunk/config/CMakeLists.txt 2008-06-24 12:00:04 UTC (rev 6673) +++ code/player/trunk/config/CMakeLists.txt 2008-06-24 13:54:42 UTC (rev 6674) @@ -2,6 +2,7 @@ amigobot_tcp.cfg amtecM5.cfg b21r_rflex_lms200.cfg + cvcam.cfg dummy.cfg erratic.cfg gazebo.cfg Added: code/player/trunk/config/cvcam.cfg =================================================================== --- code/player/trunk/config/cvcam.cfg (rev 0) +++ code/player/trunk/config/cvcam.cfg 2008-06-24 13:54:42 UTC (rev 6674) @@ -0,0 +1,13 @@ +driver +( + name "cvcam" + plugin "cvcam.so" + provides ["camera:1"] + size [384 288] +) +driver +( + name "cameracompress" + requires ["camera:1"] + provides ["camera:0"] +) Modified: code/player/trunk/server/drivers/camera/CMakeLists.txt =================================================================== --- code/player/trunk/server/drivers/camera/CMakeLists.txt 2008-06-24 12:00:04 UTC (rev 6673) +++ code/player/trunk/server/drivers/camera/CMakeLists.txt 2008-06-24 13:54:42 UTC (rev 6674) @@ -1,6 +1,7 @@ ADD_SUBDIRECTORY (v4l) ADD_SUBDIRECTORY (1394) ADD_SUBDIRECTORY (compress) +ADD_SUBDIRECTORY (cvcam) ADD_SUBDIRECTORY (imageseq) ADD_SUBDIRECTORY (sphere) ADD_SUBDIRECTORY (uvc) Added: code/player/trunk/server/drivers/camera/cvcam/CMakeLists.txt =================================================================== --- code/player/trunk/server/drivers/camera/cvcam/CMakeLists.txt (rev 0) +++ code/player/trunk/server/drivers/camera/cvcam/CMakeLists.txt 2008-06-24 13:54:42 UTC (rev 6674) @@ -0,0 +1,7 @@ +PLAYERDRIVER_OPTION (cvcam build_cvcam ON) +PLAYERDRIVER_REQUIRE_PKG (cvcam build_cvcam opencv cvcam_includeDir + cvcam_libDir cvcam_linkFlags cvcam_cFlags) +PLAYERDRIVER_ADD_DRIVER (cvcam build_cvcam + INCLUDEDIRS "${cvcam_includeDir}" LIBDIRS "${cvcam_libDir}" + LINKFLAGS "${cvcam_linkFlags}" CFLAGS "${cvcam_cFlags}" + SOURCES cvcam.cc) Added: code/player/trunk/server/drivers/camera/cvcam/cvcam.cc =================================================================== --- code/player/trunk/server/drivers/camera/cvcam/cvcam.cc (rev 0) +++ code/player/trunk/server/drivers/camera/cvcam/cvcam.cc 2008-06-24 13:54:42 UTC (rev 6674) @@ -0,0 +1,265 @@ +/* + * Player - One Hell of a Robot Server + * Copyright (C) 2000 Brian Gerkey et al. + * + * This program is free software; you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation; either version 2 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program; if not, write to the Free Software + * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + * + */ +/////////////////////////////////////////////////////////////////////////// +// +// Desc: OpenCV capture driver +// Author: Paul Osmialowski +// Date: 24 Jun 2008 +// +/////////////////////////////////////////////////////////////////////////// + +/** @ingroup drivers */ +/** @{ */ +/** @defgroup driver_cvcam cvcam + * @brief OpenCV camera capture + +The cvcam driver captures images from cameras through OpenCV infrastructure. + +@par Compile-time dependencies + +- OpenCV + +@par Provides + +- @ref interface_camera + +@par Requires + +- none + +@par Configuration requests + +- none + +@par Configuration file options + +- camindex (integer) + - Default: CV_CAP_ANY + - Index of camera image source (OpenCV specific) + +- size (integer tuple) + - Default: [0 0] + - Desired image size. This may not be honoured if the underlying driver does + not support the requested size. + Size [0 0] denotes default device image size. + +- sleep_nsec (integer) + - Default: 10000000 (=10ms which gives max 100 fps) + - timespec value for nanosleep() + +@par Example + +@verbatim +driver +( + name "cvcam" + provides ["camera:0"] +) +@endverbatim + +@author Paul Osmialowski + +*/ +/** @} */ + +#include <stddef.h> +#include <stdlib.h> +#include <string.h> +#include <assert.h> +#include <time.h> +#include <pthread.h> +#include <libplayercore/playercore.h> + +#include <opencv/cv.h> +#include <opencv/highgui.h> + +//--------------------------------- + +class CvCam : public Driver +{ + public: CvCam(ConfigFile * cf, int section); + public: virtual ~CvCam(); + + public: virtual int Setup(); + public: virtual int Shutdown(); + + // This method will be invoked on each incoming message + public: virtual int ProcessMessage(QueuePointer & resp_queue, + player_msghdr * hdr, + void * data); + + private: virtual void Main(); + + private: CvCapture * capture; + private: int camindex; + private: int desired_width; + private: int desired_height; + private: int sleep_nsec; +}; + +Driver * CvCam_Init(ConfigFile * cf, int section) +{ + return reinterpret_cast<Driver *>(new CvCam(cf, section)); +} + +void cvcam_Register(DriverTable *table) +{ + table->AddDriver("cvcam", CvCam_Init); +} + +CvCam::CvCam(ConfigFile * cf, int section) + : Driver(cf, section, true, PLAYER_MSGQUEUE_DEFAULT_MAXLEN, PLAYER_CAMERA_CODE) +{ + this->capture = NULL; + this->camindex = cf->ReadInt(section, "camindex", CV_CAP_ANY); + this->desired_width = cf->ReadTupleInt(section, "size", 0, 0); + this->desired_height = cf->ReadTupleInt(section, "size", 1, 0); + if ((this->desired_width < 0) || (this->desired_height < 0)) + { + PLAYER_ERROR("Wrong size"); + this->SetError(-1); + return; + } + this->sleep_nsec = cf->ReadInt(section, "sleep_nsec", 10000000); +} + +CvCam::~CvCam() +{ + if (this->capture) cvReleaseCapture(&(this->capture)); +} + +int CvCam::Setup() +{ + if (this->capture) cvReleaseCapture(&(this->capture)); + this->capture = cvCaptureFromCAM(this->camindex); + this->StartThread(); + return 0; +} + +int CvCam::Shutdown() +{ + StopThread(); + if (this->capture) cvReleaseCapture(&(this->capture)); + this->capture = NULL; + return 0; +} + +void CvCam::Main() +{ + struct timespec tspec; + IplImage * frame; + player_camera_data_t * data; + int i; + + if ((this->desired_width) > 0) + { + PLAYER_WARN1("Setting capture width %.4f", static_cast<double>(this->desired_width)); + cvSetCaptureProperty(this->capture, CV_CAP_PROP_FRAME_WIDTH, static_cast<double>(this->desired_width)); + } + if ((this->desired_height) > 0) + { + PLAYER_WARN1("Setting capture height %.4f", static_cast<double>(this->desired_height)); + cvSetCaptureProperty(this->capture, CV_CAP_PROP_FRAME_HEIGHT, static_cast<double>(this->desired_height)); + } + PLAYER_WARN2("Achieved capture size %.4f x %.4f", cvGetCaptureProperty(this->capture, CV_CAP_PROP_FRAME_WIDTH), cvGetCaptureProperty(this->capture, CV_CAP_PROP_FRAME_HEIGHT)); + for (;;) + { + // Go to sleep for a while (this is a polling loop). + tspec.tv_sec = 0; + tspec.tv_nsec = this->sleep_nsec; + nanosleep(&tspec, NULL); + + // Test if we are supposed to cancel this thread. + pthread_testcancel(); + + ProcessMessages(); + pthread_testcancel(); + + frame = cvQueryFrame(this->capture); + if (!frame) + { + PLAYER_ERROR("No frame!"); + continue; + } + if (frame->depth != IPL_DEPTH_8U) + { + PLAYER_ERROR1("Unsupported depth %d", frame->depth); + continue; + } + data = reinterpret_cast<player_camera_data_t *>(malloc(sizeof(player_camera_data_t))); + if (!data) + { + PLAYER_ERROR("Out of memory"); + continue; + } + assert((frame->nChannels) > 0); + data->image_count = frame->width * frame->height * frame->nChannels; + assert(data->image_count > 0); + data->image = reinterpret_cast<unsigned char *>(malloc(data->image_count)); + if (!(data->image)) + { + PLAYER_ERROR("Out of memory"); + continue; + } + data->width = frame->width; + data->height = frame->height; + data->bpp = frame->nChannels * 8; + data->fdiv = 0; + switch (data->bpp) + { + case 8: + data->format = PLAYER_CAMERA_FORMAT_MONO8; + memcpy(data->image, frame->imageData, data->image_count); + break; + case 24: + data->format = PLAYER_CAMERA_FORMAT_RGB888; + for (i = 0; i < static_cast<int>(data->image_count); i += (frame->nChannels)) + { + data->image[i] = frame->imageData[i + 2]; + data->image[i + 1] = frame->imageData[i + 1]; + data->image[i + 2] = frame->imageData[i]; + } + case 32: + data->format = PLAYER_CAMERA_FORMAT_RGB888; + for (i = 0; i < static_cast<int>(data->image_count); i += (frame->nChannels)) + { + data->image[i] = frame->imageData[i + 2]; + data->image[i + 1] = frame->imageData[i + 1]; + data->image[i + 2] = frame->imageData[i]; + data->image[i + 3] = frame->imageData[i + 3]; + } + break; + default: + PLAYER_ERROR1("Unsupported image depth %d", data->bpp); + data->bpp = 0; + } + assert(data->bpp > 0); + data->compression = PLAYER_CAMERA_COMPRESS_RAW; + this->Publish(device_addr, PLAYER_MSGTYPE_DATA, PLAYER_CAMERA_DATA_STATE, reinterpret_cast<void *>(data), 0, NULL, false); + // copy = false, don't dispose anything here + pthread_testcancel(); + } +} + +int CvCam::ProcessMessage(QueuePointer & resp_queue, player_msghdr * hdr, void * data) +{ + assert(hdr); + return -1; +} This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <th...@us...> - 2008-06-29 04:40:25
|
Revision: 6712 http://playerstage.svn.sourceforge.net/playerstage/?rev=6712&view=rev Author: thjc Date: 2008-06-29 04:40:30 -0700 (Sun, 29 Jun 2008) Log Message: ----------- removed mistakenly added dirs Removed Paths: ------------- code/player/trunk/Player_Trunk/ code/player/trunk/Stage/ This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-07-01 20:58:46
|
Revision: 6727 http://playerstage.svn.sourceforge.net/playerstage/?rev=6727&view=rev Author: gbiggs Date: 2008-07-01 20:58:53 -0700 (Tue, 01 Jul 2008) Log Message: ----------- Some work to make Player compile on QNX and Solaris Modified Paths: -------------- code/player/trunk/cmake/internal/SearchForStuff.cmake code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/libplayersd/CMakeLists.txt code/player/trunk/server/libplayerdrivers/CMakeLists.txt Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake =================================================================== --- code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-02 03:25:30 UTC (rev 6726) +++ code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-02 03:58:53 UTC (rev 6727) @@ -4,9 +4,16 @@ INCLUDE (CheckIncludeFiles) INCLUDE (CheckLibraryExists) +IF (PLAYER_OS_QNX) + SET (CMAKE_REQUIRED_LIBRARIES socket) +ELSEIF (PLAYER_OS_SOLARIS) + SET (CMAKE_REQUIRED_LIBRARIES socket nsl) +ENDIF (PLAYER_OS_QNX) +CHECK_FUNCTION_EXISTS (getaddrinfo HAVE_GETADDRINFO) +SET (CMAKE_REQUIRED_LIBRARIES) + CHECK_FUNCTION_EXISTS (cfmakeraw HAVE_CFMAKERAW) CHECK_FUNCTION_EXISTS (dirname HAVE_DIRNAME) -CHECK_FUNCTION_EXISTS (getaddrinfo HAVE_GETADDRINFO) CHECK_LIBRARY_EXISTS (ltdl lt_dlopenext "" HAVE_LIBLTDL) CHECK_INCLUDE_FILES (linux/joystick.h HAVE_LINUX_JOYSTICK_H) CHECK_FUNCTION_EXISTS (poll HAVE_POLL) @@ -83,3 +90,9 @@ LIST_TO_STRING (GDKPIXBUF_CFLAGS "${GDKPIXBUF_PKG_CFLAGS}") ENDIF (GDKPIXBUF_PKG_FOUND) ENDIF (NOT PKG_CONFIG_FOUND) + +IF (PLAYER_OS_QNX) + SET (PTHREAD_LIB) +ELSE (PLAYER_OS_QNX) + SET (PTHREAD_LIB -lpthread) +ENDIF (PLAYER_OS_QNX) Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-07-02 03:25:30 UTC (rev 6726) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-07-02 03:58:53 UTC (rev 6727) @@ -62,20 +62,30 @@ # playerxdr and used here. Those functions should go into a separate # library. SET (coreLibs playerutils playererror playerxdr pthread) -SET (corePCLibs "-lpthread") -PLAYER_ADD_LINK_LIB (pthread) +IF (PLAYER_OS_QNX) + SET (corePCLibs) +ELSE (PLAYER_OS_QNX) + SET (corePCLibs "-lpthread") + PLAYER_ADD_LINK_LIB (pthread) +ENDIF (NOT PLAYER_OS_QNX) IF (HAVE_CLOCK_GETTIME) - SET (coreLibs ${coreLibs} rt) - SET (corePCLibs "${corePCLibs} -lrt") - PLAYER_ADD_LINK_LIB (rt) + SET (coreLibs ${coreLibs} rt) + SET (corePCLibs "${corePCLibs} -lrt") + PLAYER_ADD_LINK_LIB (rt) ELSE (HAVE_CLOCK_GETTIME) - SET (playercoreSrcs ${playercoreSrcs} ${PROJECT_SOURCE_DIR}/replace/clock_gettime.c) + SET (playercoreSrcs ${playercoreSrcs} ${PROJECT_SOURCE_DIR}/replace/clock_gettime.c) ENDIF (HAVE_CLOCK_GETTIME) IF (HAVE_LIBLTDL) - SET (coreLibs ${coreLibs} ltdl dl) - SET (corePCLibs "${corePCLibs} -lltdl -dl") - PLAYER_ADD_LINK_LIB (ltdl dl) + IF (PLAYER_OS_QNX) + SET (coreLibs ${coreLibs} ltdl) + SET (corePCLibs "${corePCLibs} -lltdl") + PLAYER_ADD_LINK_LIB (ltdl) + ELSE (PLAYER_OS_QNX) + SET (coreLibs ${coreLibs} ltdl dl) + SET (corePCLibs "${corePCLibs} -lltdl -ldl") + PLAYER_ADD_LINK_LIB (ltdl dl) + ENDIF (PLAYER_OS_QNX) ENDIF (HAVE_LIBLTDL) IF (NOT HAVE_DIRNAME) SET (playercoreSrcs ${playercoreSrcs} ${PROJECT_SOURCE_DIR}/replace/dirname.c) Modified: code/player/trunk/libplayersd/CMakeLists.txt =================================================================== --- code/player/trunk/libplayersd/CMakeLists.txt 2008-07-02 03:25:30 UTC (rev 6726) +++ code/player/trunk/libplayersd/CMakeLists.txt 2008-07-02 03:58:53 UTC (rev 6727) @@ -8,7 +8,7 @@ PLAYER_ADD_LIBRARY (playersd ${playersdSrcs}) TARGET_LINK_LIBRARIES (playersd playererror playerutils) PLAYER_ADD_LINK_LIB (dns_sd) - PLAYER_MAKE_PKGCONFIG ("playersd" "Player service discovery library - part of the Player Project" "playererror playerutils" "" "" "-ldns_sd -lpthread") + PLAYER_MAKE_PKGCONFIG ("playersd" "Player service discovery library - part of the Player Project" "playererror playerutils" "" "" "-ldns_sd ${PTHREAD_LIB}") PLAYER_INSTALL_HEADERS (playersd playersd.h) ENDIF (HAVE_PLAYERSD) \ No newline at end of file Modified: code/player/trunk/server/libplayerdrivers/CMakeLists.txt =================================================================== --- code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-07-02 03:25:30 UTC (rev 6726) +++ code/player/trunk/server/libplayerdrivers/CMakeLists.txt 2008-07-02 03:58:53 UTC (rev 6727) @@ -91,6 +91,6 @@ ENDIF (PLAYER_DRIVERSLIB_LINKFLAGS) # Package config file for libplayerdrivers -PLAYER_MAKE_PKGCONFIG ("playerdrivers" "Player driver library - part of the Player Project" "playercore" "" "" "-lpthread") +PLAYER_MAKE_PKGCONFIG ("playerdrivers" "Player driver library - part of the Player Project" "playercore" "" "" "${PTHREAD_LIB}") PLAYER_INSTALL_HEADERS (playerdrivers driverregistry.h) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-07-02 19:26:26
|
Revision: 6747 http://playerstage.svn.sourceforge.net/playerstage/?rev=6747&view=rev Author: gbiggs Date: 2008-07-02 19:26:35 -0700 (Wed, 02 Jul 2008) Log Message: ----------- Added separate options for building RTK and including it in drivers. Now playerv builds by default again. Modified Paths: -------------- code/player/trunk/cmake/internal/GeneralCompileOptions.cmake code/player/trunk/playerconfig.h.in code/player/trunk/rtk2/CMakeLists.txt code/player/trunk/utils/playerv/CMakeLists.txt Modified: code/player/trunk/cmake/internal/GeneralCompileOptions.cmake =================================================================== --- code/player/trunk/cmake/internal/GeneralCompileOptions.cmake 2008-07-03 00:27:06 UTC (rev 6746) +++ code/player/trunk/cmake/internal/GeneralCompileOptions.cmake 2008-07-03 02:26:35 UTC (rev 6747) @@ -3,7 +3,12 @@ SET (DEBUG_LEVEL NONE CACHE STRING "Level of debug code to be compiled: none, low, medium or high") IF (WITH_GTK) - OPTION (INCLUDE_RTKGUI "Include the RTK GUI in the server." OFF) + OPTION (INCLUDE_RTK "Build the RTK GUI library." ON) + IF (INCLUDE_RTK) + OPTION (INCLUDE_RTKGUI "Include the RTK GUI in the server." OFF) + ELSE (INCLUDE_RTK) + SET (INCLUDE_RTKGUI OFF CACHE BOOL "Include the RTK GUI in the server." FORCE) + ENDIF (INCLUDE_RTK) ENDIF (WITH_GTK) OPTION (BUILD_SHARED_LIBS "Build the Player libraries as shared libraries." ON) Modified: code/player/trunk/playerconfig.h.in =================================================================== --- code/player/trunk/playerconfig.h.in 2008-07-03 00:27:06 UTC (rev 6746) +++ code/player/trunk/playerconfig.h.in 2008-07-03 02:26:35 UTC (rev 6747) @@ -7,6 +7,7 @@ #cmakedefine HAVE_ROUND 1 #cmakedefine HAVE_STDINT_H 1 #cmakedefine HAVE_COMPRESSBOUND 1 +#cmakedefine INCLUDE_RTK 1 #cmakedefine INCLUDE_RTKGUI 1 #cmakedefine HAVE_CLOCK_GETTIME 1 Modified: code/player/trunk/rtk2/CMakeLists.txt =================================================================== --- code/player/trunk/rtk2/CMakeLists.txt 2008-07-03 00:27:06 UTC (rev 6746) +++ code/player/trunk/rtk2/CMakeLists.txt 2008-07-03 02:26:35 UTC (rev 6747) @@ -1,4 +1,4 @@ -IF (WITH_GTK AND INCLUDE_RTKGUI) +IF (WITH_GTK AND INCLUDE_RTK) SET (rtkSrcs rtk.c rtk_canvas.c rtk_canvas_movie.c @@ -12,4 +12,4 @@ COMPILE_FLAGS "${GNOMECANVAS_CFLAGS} ${GTK_CFLAGS} ${GDKPIXBUF_CFLAGS}") SET_TARGET_PROPERTIES (rtk PROPERTIES LINK_FLAGS "${GNOMECANVAS_LINKFLAGS} ${GTK_LINKFLAGS} ${GDKPIXBUF_LINKFLAGS}") -ENDIF (WITH_GTK AND INCLUDE_RTKGUI) \ No newline at end of file +ENDIF (WITH_GTK AND INCLUDE_RTK) \ No newline at end of file Modified: code/player/trunk/utils/playerv/CMakeLists.txt =================================================================== --- code/player/trunk/utils/playerv/CMakeLists.txt 2008-07-03 00:27:06 UTC (rev 6746) +++ code/player/trunk/utils/playerv/CMakeLists.txt 2008-07-03 02:26:35 UTC (rev 6747) @@ -1,4 +1,4 @@ -IF (WITH_GTK AND INCLUDE_RTKGUI) +IF (WITH_GTK AND INCLUDE_RTK) SET (playervSrcs playerv.c playerv.h registry.c @@ -32,6 +32,6 @@ COMPILE_FLAGS "${GTK_CFLAGS}") SET_TARGET_PROPERTIES (playerv PROPERTIES LINK_FLAGS "${GTK_LINKFLAGS}") -ELSE (WITH_GTK AND INCLUDE_RTKGUI) +ELSE (WITH_GTK AND INCLUDE_RTK) MESSAGE (STATUS "playerv will not be built - GTK not found or RTK disabled.") -ENDIF (WITH_GTK AND INCLUDE_RTKGUI) \ No newline at end of file +ENDIF (WITH_GTK AND INCLUDE_RTK) \ No newline at end of file This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-07-03 19:44:18
|
Revision: 6756 http://playerstage.svn.sourceforge.net/playerstage/?rev=6756&view=rev Author: gbiggs Date: 2008-07-03 19:44:27 -0700 (Thu, 03 Jul 2008) Log Message: ----------- Fixes to make player compile on QNX and Solaris Modified Paths: -------------- code/player/trunk/client_libs/libplayerc/CMakeLists.txt code/player/trunk/client_libs/libplayerc/client.c code/player/trunk/client_libs/libplayerc++/CMakeLists.txt code/player/trunk/cmake/internal/SearchForStuff.cmake code/player/trunk/libplayercore/CMakeLists.txt code/player/trunk/libplayertcp/CMakeLists.txt code/player/trunk/libplayerxdr/CMakeLists.txt code/player/trunk/libplayerxdr/functiontable.c code/player/trunk/libplayerxdr/functiontable.h code/player/trunk/playerconfig.h.in code/player/trunk/replace/clock_gettime.c code/player/trunk/server/drivers/rfid/rfi341_protocol.cc Modified: code/player/trunk/client_libs/libplayerc/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/client_libs/libplayerc/CMakeLists.txt 2008-07-04 02:44:27 UTC (rev 6756) @@ -59,16 +59,18 @@ TARGET_LINK_LIBRARIES (playerc playerxdr playerutils playererror ${PLAYERC_EXTRA_LINK_LIBRARIES}) IF (HAVE_JPEG) TARGET_LINK_LIBRARIES (playerc playerjpeg) - PLAYERC_ADD_LINK_LIB (jpeg) ENDIF (HAVE_JPEG) IF (HAVE_Z) TARGET_LINK_LIBRARIES (playerc z) - PLAYERC_ADD_LINK_LIB (z) ENDIF (HAVE_Z) IF (HAVE_GEOS) TARGET_LINK_LIBRARIES (playerc ${GEOS_LIBS}) - PLAYERC_ADD_LINK_LIB (${GEOS_LIBS}) ENDIF (HAVE_GEOS) +IF (PLAYER_OS_QNX) + TARGET_LINK_LIBRARIES (playerc socket rpc) +ELSEIF (PLAYER_OS_SOLARIS) + TARGET_LINK_LIBRARIES (playerc socket nsl) +ENDIF (PLAYER_OS_QNX) PLAYER_INSTALL_HEADERS (playerc playerc.h) Modified: code/player/trunk/client_libs/libplayerc/client.c =================================================================== --- code/player/trunk/client_libs/libplayerc/client.c 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/client_libs/libplayerc/client.c 2008-07-04 02:44:27 UTC (rev 6756) @@ -1180,7 +1180,7 @@ if((encode_msglen = (*packfunc)(client->write_xdrdata + PLAYERXDR_MSGHDR_SIZE, PLAYER_MAX_MESSAGE_SIZE - PLAYERXDR_MSGHDR_SIZE, - data, PLAYERXDR_ENCODE)) < 0) + (void*) data, PLAYERXDR_ENCODE)) < 0) { PLAYERC_ERR4("encoding failed on message from %s:%u with type %s:%u", interf_to_str(header->addr.interf), header->addr.index, msgtype_to_str(header->type), header->subtype); Modified: code/player/trunk/client_libs/libplayerc++/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/client_libs/libplayerc++/CMakeLists.txt 2008-07-04 02:44:27 UTC (rev 6756) @@ -1,6 +1,11 @@ ADD_SUBDIRECTORY (test) -OPTION (BUILD_PLAYERCC "Build the C++ client library" ON) +IF (HAVE_STL) + OPTION (BUILD_PLAYERCC "Build the C++ client library" ON) +ELSE (HAVE_STL) + MESSAGE (STATUS "PlayerC++ client library will not be built - STL is not available.") + SET (BUILD_PLAYERCC OFF CACHE BOOL "Build the C++ client library" FORCE) +ENDIF (HAVE_STL) IF (PLAYER_OS_OSX AND CMAKE_MAJOR_VERSION EQUAL 2 AND CMAKE_MINOR_VERSION EQUAL 4) # Boost is off by default on OS X under CMake 2.4 @@ -191,6 +196,13 @@ PLAYER_ADD_LIBRARY (playerc++ ${playerccSrcs} ${playercppconfig_h}) TARGET_LINK_LIBRARIES (playerc++ playerxdr playerutils playerc ${PLAYERCC_EXTRA_LINK_LIBRARIES}) + IF (PLAYER_OS_SOLARIS) + TARGET_LINK_LIBRARIES (playerc++ socket nsl) + SET (pkgconfigLibFlags "-lsocket -lnsl") + ELSE (PLAYER_OS_SOLARIS) + SET (pkgconfigLibFlags) + ENDIF (PLAYER_OS_SOLARIS) + PLAYER_MAKE_PKGCONFIG ("playerc++" "C++ wrapper for libplayerc - part of the Player Project" "playerxdr playerc" "" "-I${boostIncludeDir}" Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake =================================================================== --- code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-04 02:44:27 UTC (rev 6756) @@ -12,6 +12,16 @@ CHECK_FUNCTION_EXISTS (getaddrinfo HAVE_GETADDRINFO) SET (CMAKE_REQUIRED_LIBRARIES) +IF (PLAYER_OS_QNX) + SET (CMAKE_REQUIRED_LIBRARIES rpc) +ENDIF (PLAYER_OS_QNX) +CHECK_FUNCTION_EXISTS (xdr_free HAVE_XDR) +IF (NOT HAVE_XDR) + MESSAGE (STATUS "XDR was not found. This is necessary for Player to function.") +ENDIF (NOT HAVE_XDR) +CHECK_FUNCTION_EXISTS (xdr_longlong_t HAVE_XDR_LONGLONG_T) +SET (CMAKE_REQUIRED_LIBRARIES) + CHECK_FUNCTION_EXISTS (cfmakeraw HAVE_CFMAKERAW) CHECK_FUNCTION_EXISTS (dirname HAVE_DIRNAME) CHECK_LIBRARY_EXISTS (ltdl lt_dlopenext "" HAVE_LIBLTDL) @@ -93,6 +103,20 @@ IF (PLAYER_OS_QNX) SET (PTHREAD_LIB) + SET (SOCKET_LIBS socket) + SET (SOCKET_LIBS_FLAGS -lsocket) +ELSEIF (PLAYER_OS_SOLARIS) + SET (PTHREAD_LIB -lpthread) + SET (SOCKET_LIBS socket nsl) + SET (SOCKET_LIBS_FLAGS "-lsocket -lnsl") ELSE (PLAYER_OS_QNX) SET (PTHREAD_LIB -lpthread) + SET (SOCKET_LIBS) + SET (SOCKET_LIBS_FLAGS) ENDIF (PLAYER_OS_QNX) + +# STL check +SET (testSTLSource ${CMAKE_CURRENT_BINARY_DIR}/CMakeTmp/test_stl.cpp) +FILE (WRITE ${testSTLSource} + "#include <string>\nint main () {std::string a = \"blag\"; return 0;}\n") +TRY_COMPILE (HAVE_STL ${CMAKE_CURRENT_BINARY_DIR} ${testSTLSource}) Modified: code/player/trunk/libplayercore/CMakeLists.txt =================================================================== --- code/player/trunk/libplayercore/CMakeLists.txt 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/libplayercore/CMakeLists.txt 2008-07-04 02:44:27 UTC (rev 6756) @@ -61,10 +61,11 @@ # from the fact that message cloning functions are auto-generated into # playerxdr and used here. Those functions should go into a separate # library. -SET (coreLibs playerutils playererror playerxdr pthread) +SET (coreLibs playerutils playererror playerxdr) IF (PLAYER_OS_QNX) SET (corePCLibs) ELSE (PLAYER_OS_QNX) + SET (coreLibs ${coreLibs} pthread) SET (corePCLibs "-lpthread") PLAYER_ADD_LINK_LIB (pthread) ENDIF (PLAYER_OS_QNX) Modified: code/player/trunk/libplayertcp/CMakeLists.txt =================================================================== --- code/player/trunk/libplayertcp/CMakeLists.txt 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/libplayertcp/CMakeLists.txt 2008-07-04 02:44:27 UTC (rev 6756) @@ -3,6 +3,17 @@ INCLUDE_DIRECTORIES (${PROJECT_BINARY_DIR}/libplayercore) +IF (PLAYER_OS_QNX) + SET (socketLibs socket) + SET (socketLibsFlags -lsocket) +ELSEIF (PLAYER_OS_SOLARIS) + SET (socketLibs socket nsl) + SET (socketLibsFlags "-lsocket -lnsl") +ELSE (PLAYER_OS_QNX) + SET (socketLibs) + SET (socketLibsFlags) +ENDIF (PLAYER_OS_QNX) + IF (INCLUDE_TCP) OPTION (ENABLE_TCP_NODELAY "Turn off Nagel's buffering algorithm (which may increase socket latency when used)" OFF) @@ -14,12 +25,17 @@ SET (playertcpSrcs ${playertcpSrcs} ${PROJECT_SOURCE_DIR}/replace/compressBound.c) ENDIF (NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playertcp ${playertcpSrcs}) - TARGET_LINK_LIBRARIES (playertcp playercore playererror playerutils playerxdr) + TARGET_LINK_LIBRARIES (playertcp playercore playererror playerutils playerxdr ${SOCKET_LIBS}) + IF (SOCKET_LIBS) + PLAYER_ADD_LINK_LIB (${SOCKET_LIBS}) + ENDIF (SOCKET_LIBS) IF (HAVE_Z) TARGET_LINK_LIBRARIES (playertcp z) PLAYER_ADD_LINK_LIB (z) + SET (zLibFlag -lz) ENDIF (HAVE_Z) - PLAYER_MAKE_PKGCONFIG ("playertcp" "Player TCP messaging library - part of the Player Project" "playererror playercore" "" "" "") + PLAYER_MAKE_PKGCONFIG ("playertcp" "Player TCP messaging library - part of the Player Project" + "playererror playercore" "" "" "${zLibFlag} ${SOCKET_LIBS_FLAGS}") PLAYER_INSTALL_HEADERS (playertcp playertcp.h) ENDIF (INCLUDE_TCP) @@ -33,9 +49,12 @@ SET (playerudpSrcs ${playerudpSrcs} ${PROJECT_SOURCE_DIR}/replace/compressBound.c) ENDIF (NOT HAVE_COMPRESSBOUND) PLAYER_ADD_LIBRARY (playerudp ${playerudpSrcs}) - TARGET_LINK_LIBRARIES (playerudp playercore playererror playerutils playerxdr) - TARGET_LINK_LIBRARIES (playerudp z) - PLAYER_MAKE_PKGCONFIG ("playerudp" "Player UDP messaging library - part of the Player Project" "playererror playercore" "" "" "") + TARGET_LINK_LIBRARIES (playerudp playercore playererror playerutils playerxdr ${SOCKET_LIBS} z) + IF (SOCKET_LIBS) + PLAYER_ADD_LINK_LIB (${SOCKET_LIBS} z) + ENDIF (SOCKET_LIBS) + PLAYER_MAKE_PKGCONFIG ("playerudp" "Player UDP messaging library - part of the Player Project" + "playererror playercore" "" "" "-lz ${SOCKET_LIBS_FLAGS}") PLAYER_INSTALL_HEADERS (playertcp playerudp.h) ENDIF (INCLUDE_UDP) Modified: code/player/trunk/libplayerxdr/CMakeLists.txt =================================================================== --- code/player/trunk/libplayerxdr/CMakeLists.txt 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/libplayerxdr/CMakeLists.txt 2008-07-04 02:44:27 UTC (rev 6756) @@ -36,9 +36,19 @@ functiontable.c ${functiontable_gen_h}) +IF (PLAYER_OS_QNX) + SET (xdrLibFlag -lrpc) +ELSE (PLAYER_OS_QNX) + SET (xdrLibFlag) +ENDIF (PLAYER_OS_QNX) + INCLUDE_DIRECTORIES (${CMAKE_CURRENT_BINARY_DIR}) PLAYER_ADD_LIBRARY (playerxdr ${playerxdrSrcs}) SET_SOURCE_FILES_PROPERTIES (${playerxdr_h} ${playerxdr_c} PROPERTIES GENERATED TRUE) -PLAYER_MAKE_PKGCONFIG ("playerxdr" "Player XDR messaging library - part of the Player Project" "" "" "" "") +IF (PLAYER_OS_QNX) + TARGET_LINK_LIBRARIES (playerxdr rpc) + PLAYER_ADD_LINK_LIB (rpc) +ENDIF (PLAYER_OS_QNX) +PLAYER_MAKE_PKGCONFIG ("playerxdr" "Player XDR messaging library - part of the Player Project" "" "" "" "${xdrLibFlag}") PLAYER_INSTALL_HEADERS (playerxdr ${playerxdr_h} functiontable.h) Modified: code/player/trunk/libplayerxdr/functiontable.c =================================================================== --- code/player/trunk/libplayerxdr/functiontable.c 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/libplayerxdr/functiontable.c 2008-07-04 02:44:27 UTC (rev 6756) @@ -56,6 +56,34 @@ #include "playerxdr.h" #include "functiontable.h" +#ifndef HAVE_XDR_LONGLONG_T +#include <rpc/types.h> +#include <rpc/xdr.h> + +bool_t xdr_longlong_t(XDR *xdrs, long long int *llp) +{ + long int t1, t2; + + if (xdrs->x_op == XDR_ENCODE) + { + t1 = (long) ((*llp) >> 32); + t2 = (long) (*llp); + return (XDR_PUTLONG(xdrs, &t1) && XDR_PUTLONG(xdrs, &t2)); + } + if (xdrs->x_op == XDR_DECODE) + { + if (!XDR_GETLONG(xdrs, &t1) || !XDR_GETLONG(xdrs, &t2)) + return FALSE; + *llp = ((long long int) t1) << 32; + *llp |= (uint32_t) t2; + return TRUE; + } + if (xdrs->x_op == XDR_FREE) + return TRUE; + return FALSE; +} +#endif + static playerxdr_function_t init_ftable[] = { /* This list is currently alphabetized, please keep it that way! */ Modified: code/player/trunk/libplayerxdr/functiontable.h =================================================================== --- code/player/trunk/libplayerxdr/functiontable.h 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/libplayerxdr/functiontable.h 2008-07-04 02:44:27 UTC (rev 6756) @@ -53,6 +53,12 @@ extern "C" { #endif +#ifndef HAVE_XDR_LONGLONG_T + #include <rpc/types.h> + #include <rpc/xdr.h> + bool_t xdr_longlong_t(XDR *xdrs, long long int *llp); +#endif + /** @addtogroup libplayerxdr libplayerxdr @{ */ /** Generic Prototype for a player XDR packing function */ Modified: code/player/trunk/playerconfig.h.in =================================================================== --- code/player/trunk/playerconfig.h.in 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/playerconfig.h.in 2008-07-04 02:44:27 UTC (rev 6756) @@ -10,6 +10,8 @@ #cmakedefine INCLUDE_RTK 1 #cmakedefine INCLUDE_RTKGUI 1 #cmakedefine HAVE_CLOCK_GETTIME 1 +#cmakedefine HAVE_XDR_LONGLONG_T 1 +#cmakedefine HAVE_STL 1 #ifdef HAVE_STDINT_H #include <stdint.h> Modified: code/player/trunk/replace/clock_gettime.c =================================================================== --- code/player/trunk/replace/clock_gettime.c 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/replace/clock_gettime.c 2008-07-04 02:44:27 UTC (rev 6756) @@ -20,6 +20,8 @@ * */ +#include <stddef.h> +#include <time.h> #include <sys/time.h> /* This replacement function originally written by Klass Gadeyne Modified: code/player/trunk/server/drivers/rfid/rfi341_protocol.cc =================================================================== --- code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-07-03 23:46:19 UTC (rev 6755) +++ code/player/trunk/server/drivers/rfid/rfi341_protocol.cc 2008-07-04 02:44:27 UTC (rev 6756) @@ -5,7 +5,6 @@ CVS: $Id$ */ #include <termios.h> -#include <iostream> #include <unistd.h> #include <fcntl.h> #include <libplayercore/playercore.h> This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |
From: <gb...@us...> - 2008-07-15 18:25:54
|
Revision: 6872 http://playerstage.svn.sourceforge.net/playerstage/?rev=6872&view=rev Author: gbiggs Date: 2008-07-15 18:26:03 -0700 (Tue, 15 Jul 2008) Log Message: ----------- Added missing check for jpeg presense to python bindings linking. Added options for setting locations of needed libraries. Modified Paths: -------------- code/player/trunk/CMakeLists.txt code/player/trunk/client_libs/libplayerc/bindings/python/CMakeLists.txt code/player/trunk/cmake/internal/SearchForStuff.cmake code/player/trunk/config.h.in code/player/trunk/server/drivers/camera/compress/CMakeLists.txt Modified: code/player/trunk/CMakeLists.txt =================================================================== --- code/player/trunk/CMakeLists.txt 2008-07-15 22:51:29 UTC (rev 6871) +++ code/player/trunk/CMakeLists.txt 2008-07-16 01:26:03 UTC (rev 6872) @@ -52,18 +52,16 @@ ADD_SUBDIRECTORY (client_libs) ADD_SUBDIRECTORY (libplayercore) ADD_SUBDIRECTORY (libplayerxdr) -IF (NOT PLAYER_OS_WIN) - ADD_SUBDIRECTORY (config) # Example config files - ADD_SUBDIRECTORY (libplayerjpeg) - ADD_SUBDIRECTORY (libplayertcp) - ADD_SUBDIRECTORY (libplayersd) - ADD_SUBDIRECTORY (rtk2) - ADD_SUBDIRECTORY (server) - ADD_SUBDIRECTORY (examples) - ADD_SUBDIRECTORY (utils) - ADD_SUBDIRECTORY (doc) -ENDIF (NOT PLAYER_OS_WIN) -ADD_SUBDIRECTORY (cmake) +ADD_SUBDIRECTORY (config) # Example config files +ADD_SUBDIRECTORY (libplayerjpeg) +ADD_SUBDIRECTORY (libplayertcp) +ADD_SUBDIRECTORY (libplayersd) +ADD_SUBDIRECTORY (rtk2) +ADD_SUBDIRECTORY (server) +ADD_SUBDIRECTORY (examples) +ADD_SUBDIRECTORY (utils) +ADD_SUBDIRECTORY (doc) +ADD_SUBDIRECTORY (cmake) # CMake modules for Player libraries MESSAGE (STATUS "") SET (PLAYER_EXTRA_LINK_LIBRARIES "" CACHE INTERNAL "Libs to link to" FORCE) Modified: code/player/trunk/client_libs/libplayerc/bindings/python/CMakeLists.txt =================================================================== --- code/player/trunk/client_libs/libplayerc/bindings/python/CMakeLists.txt 2008-07-15 22:51:29 UTC (rev 6871) +++ code/player/trunk/client_libs/libplayerc/bindings/python/CMakeLists.txt 2008-07-16 01:26:03 UTC (rev 6872) @@ -35,7 +35,10 @@ SWIG_ADD_MODULE (playerc python ${playerc_i}) SWIG_LINK_LIBRARIES (playerc ${PYTHON_LIBRARIES}) ADD_DEPENDENCIES (${SWIG_MODULE_playerc_REAL_NAME} playerc_oo_i_target) - TARGET_LINK_LIBRARIES (${SWIG_MODULE_playerc_REAL_NAME} playerxdr playerc playerjpeg jpeg playererror) + TARGET_LINK_LIBRARIES (${SWIG_MODULE_playerc_REAL_NAME} playerxdr playerc playererror) + IF (HAVE_JPEG) + TARGET_LINK_LIBRARIES (${SWIG_MODULE_playerc_REAL_NAME} playerjpeg) + ENDIF (HAVE_JPEG) # Generate the set up script # CONFIGURE_FILE (${CMAKE_CURRENT_SOURCE_DIR}/setup.py.cmake ${CMAKE_CURRENT_BINARY_DIR}/setup.py) Modified: code/player/trunk/cmake/internal/SearchForStuff.cmake =================================================================== --- code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-15 22:51:29 UTC (rev 6871) +++ code/player/trunk/cmake/internal/SearchForStuff.cmake 2008-07-16 01:26:03 UTC (rev 6872) @@ -26,40 +26,52 @@ CHECK_FUNCTION_EXISTS (cfmakeraw HAVE_CFMAKERAW) CHECK_FUNCTION_EXISTS (dirname HAVE_DIRNAME) -CHECK_LIBRARY_EXISTS (ltdl lt_dlopenext "" HAVE_LIBLTDL) CHECK_INCLUDE_FILES (linux/joystick.h HAVE_LINUX_JOYSTICK_H) CHECK_FUNCTION_EXISTS (poll HAVE_POLL) CHECK_INCLUDE_FILES (stdint.h HAVE_STDINT_H) CHECK_INCLUDE_FILES (strings.h HAVE_STRINGS_H) CHECK_INCLUDE_FILES (dns_sd.h HAVE_DNS_SD) IF (HAVE_DNS_SD) - CHECK_LIBRARY_EXISTS (dns_sd DNSServiceRefDeallocate "" HAVE_DNS_SD) + SET (DNS_SD_LOCATION "" CACHE STRING "Location where dns_sd is installed.") + MARK_AS_ADVANCED (DNS_SD_LOCATION) + CHECK_LIBRARY_EXISTS (dns_sd DNSServiceRefDeallocate "${DNS_SD_LOCATION}" HAVE_DNS_SD) ENDIF (HAVE_DNS_SD) +SET (LIBLTDL_LOCATION "" CACHE STRING "Location where libltdl is installed.") +MARK_AS_ADVANCED (LIBLTDL_LOCATION) +CHECK_LIBRARY_EXISTS (ltdl lt_dlopenext "${LIBLTDL_LOCATION}" HAVE_LIBLTDL) + SET (CMAKE_REQUIRED_INCLUDES math.h) SET (CMAKE_REQUIRED_LIBRARIES m) CHECK_FUNCTION_EXISTS (round HAVE_ROUND) SET (CMAKE_REQUIRED_INCLUDES) SET (CMAKE_REQUIRED_LIBRARIES) -CHECK_LIBRARY_EXISTS (jpeg jpeg_read_header "" HAVE_LIBJPEG) +SET (LIBJPEG_LOCATION "" CACHE STRING "Location where libjpeg is installed.") +MARK_AS_ADVANCED (LIBJPEG_LOCATION) +CHECK_LIBRARY_EXISTS (jpeg jpeg_read_header "${LIBJPEG_LOCATION}" HAVE_LIBJPEG) CHECK_INCLUDE_FILES ("stdio.h;jpeglib.h" HAVE_JPEGLIB_H) IF (HAVE_LIBJPEG AND HAVE_JPEGLIB_H) SET (HAVE_JPEG TRUE) ENDIF (HAVE_LIBJPEG AND HAVE_JPEGLIB_H) + SET (CMAKE_REQUIRED_INCLUDES zlib.h) SET (CMAKE_REQUIRED_LIBRARIES z) CHECK_FUNCTION_EXISTS (compressBound HAVE_COMPRESSBOUND) SET (CMAKE_REQUIRED_INCLUDES) SET (CMAKE_REQUIRED_LIBRARIES) -CHECK_LIBRARY_EXISTS (z compress2 "" HAVE_LIBZ) +SET (LIBZ_LOCATION "" CACHE STRING "Location where libz is installed.") +MARK_AS_ADVANCED (LIBZ_LOCATION) +CHECK_LIBRARY_EXISTS (z compress2 "${LIBZ_LOCATION}" HAVE_LIBZ) CHECK_INCLUDE_FILES (zlib.h HAVE_ZLIB_H) IF (HAVE_LIBZ AND HAVE_ZLIB_H) SET (HAVE_Z TRUE) ENDIF (HAVE_LIBZ AND HAVE_ZLIB_H) -CHECK_LIBRARY_EXISTS (rt clock_gettime "" HAVE_LIBRT) +SET (LIBRT_LOCATION "" CACHE STRING "Location where librt is installed.") +MARK_AS_ADVANCED (LIBRT_LOCATION) +CHECK_LIBRARY_EXISTS (rt clock_gettime "${LIBRT_LOCATION}" HAVE_LIBRT) SET (CMAKE_REQUIRED_LIBRARIES rt) CHECK_FUNCTION_EXISTS (clock_gettime HAVE_CLOCK_GETTIME_FUNC) SET (CMAKE_REQUIRED_LIBRARIES) Modified: code/player/trunk/config.h.in =================================================================== --- code/player/trunk/config.h.in 2008-07-15 22:51:29 UTC (rev 6871) +++ code/player/trunk/config.h.in 2008-07-16 01:26:03 UTC (rev 6872) @@ -10,8 +10,6 @@ #cmakedefine ENABLE_TCP_NODELAY 1 #cmakedefine HAVE_GETADDRINFO 1 -//#cmakedefine HAVE_JPEGLIB_H 1 -//#cmakedefine HAVE_LIBJPEG 1 #cmakedefine HAVE_JPEG 1 #cmakedefine HAVE_LIBZ 1 #cmakedefine HAVE_LINUX_JOYSTICK_H 1 Modified: code/player/trunk/server/drivers/camera/compress/CMakeLists.txt =================================================================== --- code/player/trunk/server/drivers/camera/compress/CMakeLists.txt 2008-07-15 22:51:29 UTC (rev 6871) +++ code/player/trunk/server/drivers/camera/compress/CMakeLists.txt 2008-07-16 01:26:03 UTC (rev 6872) @@ -1,7 +1,12 @@ -PLAYERDRIVER_OPTION (cameracompress build_cameracompress ON) -PLAYERDRIVER_REQUIRE_HEADER (cameracompress build_cameracompress jpeglib.h stdio.h) -PLAYERDRIVER_ADD_DRIVER (cameracompress build_cameracompress LINKFLAGS "-ljpeg" SOURCES cameracompress.cc) +IF (HAVE_JPEG) + PLAYERDRIVER_OPTION (cameracompress build_cameracompress ON) + PLAYERDRIVER_REQUIRE_HEADER (cameracompress build_cameracompress jpeglib.h stdio.h) + PLAYERDRIVER_ADD_DRIVER (cameracompress build_cameracompress LINKFLAGS "-ljpeg" SOURCES cameracompress.cc) -PLAYERDRIVER_OPTION (camerauncompress build_camerauncompress ON) -PLAYERDRIVER_REQUIRE_HEADER (camerauncompress build_camerauncompress jpeglib.h stdio.h) -PLAYERDRIVER_ADD_DRIVER (camerauncompress build_camerauncompress LINKFLAGS "-ljpeg" SOURCES camerauncompress.cc) + PLAYERDRIVER_OPTION (camerauncompress build_camerauncompress ON) + PLAYERDRIVER_REQUIRE_HEADER (camerauncompress build_camerauncompress jpeglib.h stdio.h) + PLAYERDRIVER_ADD_DRIVER (camerauncompress build_camerauncompress LINKFLAGS "-ljpeg" SOURCES camerauncompress.cc) +ELSE (HAVE_JPEG) + PLAYERDRIVER_OPTION (cameracompress build_cameracompress OFF "playerjpeg is not available.") + PLAYERDRIVER_OPTION (camerauncompress build_camerauncompress OFF "playerjpeg is not available.") +ENDIF (HAVE_JPEG) This was sent by the SourceForge.net collaborative development platform, the world's largest Open Source development site. |