Revision: 7206
          http://playerstage.svn.sourceforge.net/playerstage/?rev=7206&view=rev
Author:   thjc
Date:     2008-12-18 19:58:30 +0000 (Thu, 18 Dec 2008)

Log Message:
-----------
Merged assert fixes from 7204
also some cmake fixes for postgis/vec2map drivers

Modified Paths:
--------------
    code/player/trunk/server/drivers/base/imagebase.cc
    code/player/trunk/server/drivers/camera/1394/camera1394.cc
    code/player/trunk/server/drivers/camera/compress/cameracompress.cc
    code/player/trunk/server/drivers/camera/compress/camerauncompress.cc
    code/player/trunk/server/drivers/camera/sphere/sphere_mixed.cc
    code/player/trunk/server/drivers/camera/v4l/camerav4l.cc
    code/player/trunk/server/drivers/fiducial/laserbar.cc
    code/player/trunk/server/drivers/fiducial/laserbarcode.cc
    code/player/trunk/server/drivers/fiducial/laservisualbarcode.cc
    code/player/trunk/server/drivers/fiducial/laservisualbw.cc
    code/player/trunk/server/drivers/imu/XSensMT.cc
    code/player/trunk/server/drivers/imu/nimuplayer.cpp
    code/player/trunk/server/drivers/laser/sicklms400.cc
    code/player/trunk/server/drivers/map/maptransform.cc
    code/player/trunk/server/drivers/mcom/lifomcom.cc
    code/player/trunk/server/drivers/mixed/clodbuster/clodbuster.cc
    code/player/trunk/server/drivers/mixed/cmucam2/cmucam2.cc
    code/player/trunk/server/drivers/mixed/evolution/er1/er.cc
    code/player/trunk/server/drivers/mixed/garcia/garcia_mixed.cc
    code/player/trunk/server/drivers/mixed/khepera/khepera.cc
    code/player/trunk/server/drivers/mixed/reb/reb.cc
    code/player/trunk/server/drivers/mixed/sr3000/sr3000.cc
    code/player/trunk/server/drivers/position/ascension/flockofbirds.cc
    code/player/trunk/server/drivers/position/bumpersafe/bumpersafe.cc
    code/player/trunk/server/drivers/position/isense/inertiacube2.cc
    code/player/trunk/server/drivers/position/lasersafe/lasersafe.cc
    code/player/trunk/server/drivers/position/mbicp/mbicp_driver.cc
    code/player/trunk/server/drivers/position/roboteq/roboteq.cc
    code/player/trunk/server/drivers/ptz/amtecpowercube.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/sickrfi341.cc
    code/player/trunk/server/drivers/speech/festival.cc
    code/player/trunk/server/drivers/vectormap/CMakeLists.txt
    code/player/trunk/server/drivers/vectormap/vec2map.cc
    code/player/trunk/server/drivers/wifi/linuxwifi.cc
    code/player/trunk/server/drivers/wsn/accel_calib.cc
    code/player/trunk/server/drivers/wsn/mica2.cc
    code/player/trunk/server/drivers/wsn/rcore_xbridge.cc

Property Changed:
----------------
    code/player/trunk/


Property changes on: code/player/trunk
___________________________________________________________________
Modified: svn:mergeinfo
   - 
/code/player/branches/release-2-1-patches:6672-6673,6738,6834,6886,6905,6930,6936,6946,6951,6955,6975,6979-6981,6985,6987-6996
/code/player/trunk:6985
   + 
/code/player/branches/release-2-1-patches:6672-6673,6738,6834,6886,6905,6930,6936,6946,6951,6955,6975,6979-6981,6985,6987-6996,7204
/code/player/trunk:6985

Modified: code/player/trunk/server/drivers/base/imagebase.cc
===================================================================
--- code/player/trunk/server/drivers/base/imagebase.cc  2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/base/imagebase.cc  2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -120,13 +120,13 @@
 int ImageBase::ProcessMessage (QueuePointer &resp_queue, player_msghdr * hdr, 
void * data)
 {
   uint32_t new_image_count;
-  player_camera_data_t * compdata = reinterpret_cast<player_camera_data_t 
*>(data);
 
   assert(hdr);
-  assert(compdata);
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, 
PLAYER_CAMERA_DATA_STATE, camera_addr))
   {
+       assert(data);
+       player_camera_data_t * compdata = reinterpret_cast<player_camera_data_t 
*>(data);
        Lock();
        if (!HaveData)
        {

Modified: code/player/trunk/server/drivers/camera/1394/camera1394.cc
===================================================================
--- code/player/trunk/server/drivers/camera/1394/camera1394.cc  2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/camera/1394/camera1394.cc  2008-12-18 
19:58:30 UTC (rev 7206)
@@ -1157,7 +1157,6 @@
                               void * data)
 {
   assert(hdr);
-  assert(data);
 
   /* We currently don't support any messages, but if we do...
   if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ,

Modified: code/player/trunk/server/drivers/camera/compress/cameracompress.cc
===================================================================
--- code/player/trunk/server/drivers/camera/compress/cameracompress.cc  
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/camera/compress/cameracompress.cc  
2008-12-18 19:58:30 UTC (rev 7206)
@@ -204,10 +204,10 @@
                                void * data)
 {
   assert(hdr);
-  assert(data);
 
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_DATA, 
PLAYER_CAMERA_DATA_STATE, camera_id))
   {
+       assert(data);
     player_camera_data_t * recv = reinterpret_cast<player_camera_data_t * > 
(data);
     ProcessImage(*recv);
     return 0;

Modified: code/player/trunk/server/drivers/camera/compress/camerauncompress.cc
===================================================================
--- code/player/trunk/server/drivers/camera/compress/camerauncompress.cc        
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/camera/compress/camerauncompress.cc        
2008-12-18 19:58:30 UTC (rev 7206)
@@ -198,10 +198,10 @@
                                void * data)
 {
   assert(hdr);
-  assert(data);
 
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_DATA, 
PLAYER_CAMERA_DATA_STATE, camera_id))
   {
+       assert(data);
     if(hdr->size < sizeof(player_camera_data_t))
     {
       PLAYER_WARN("Not enough camera data recieved");

Modified: code/player/trunk/server/drivers/camera/sphere/sphere_mixed.cc
===================================================================
--- code/player/trunk/server/drivers/camera/sphere/sphere_mixed.cc      
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/camera/sphere/sphere_mixed.cc      
2008-12-18 19:58:30 UTC (rev 7206)
@@ -419,7 +419,6 @@
                                  void* data)
 {
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD,
                            PLAYER_PTZ_CMD_STATE, mPtzAddr))

Modified: code/player/trunk/server/drivers/camera/v4l/camerav4l.cc
===================================================================
--- code/player/trunk/server/drivers/camera/v4l/camerav4l.cc    2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/camera/v4l/camerav4l.cc    2008-12-18 
19:58:30 UTC (rev 7206)
@@ -533,8 +533,6 @@
   if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ,
                            PLAYER_CAMERA_REQ_GET_GEOM, this->device_addr))
   {
-    assert(data);
-    assert(hdr->size == sizeof(player_position2d_data_t));
     ProcessGetGeom(hdr, *reinterpret_cast<player_camera_data_t *> (data));
     return(0);
 

Modified: code/player/trunk/server/drivers/fiducial/laserbar.cc
===================================================================
--- code/player/trunk/server/drivers/fiducial/laserbar.cc       2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/fiducial/laserbar.cc       2008-12-18 
19:58:30 UTC (rev 7206)
@@ -287,7 +287,6 @@
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_DATA,
                             PLAYER_LASER_DATA_SCAN, this->laser_addr))
   {
-       //assert(hdr->size == sizeof(player_laser_data_t));
        player_laser_data_t *laser_data = reinterpret_cast<player_laser_data_t 
* > (data);
 
        this->Lock();

Modified: code/player/trunk/server/drivers/fiducial/laserbarcode.cc
===================================================================
--- code/player/trunk/server/drivers/fiducial/laserbarcode.cc   2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/fiducial/laserbarcode.cc   2008-12-18 
19:58:30 UTC (rev 7206)
@@ -278,11 +278,9 @@
 int LaserBarcode::ProcessMessage (QueuePointer &resp_queue, player_msghdr * 
hdr, void * data)
 {
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_LASER_DATA_SCAN, 
laser_id))
   {
-    assert(hdr->size == sizeof(player_laser_data_t));
     laser_data = *reinterpret_cast<player_laser_data_t * > (data);
 
     // Analyse the laser data

Modified: code/player/trunk/server/drivers/fiducial/laservisualbarcode.cc
===================================================================
--- code/player/trunk/server/drivers/fiducial/laservisualbarcode.cc     
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/fiducial/laservisualbarcode.cc     
2008-12-18 19:58:30 UTC (rev 7206)
@@ -412,11 +412,9 @@
 int LaserVisualBarcode::ProcessMessage (QueuePointer &resp_queue, 
player_msghdr * hdr, void * data)
 {
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_LASER_DATA_SCAN, 
laser_id))
   {
-    assert(hdr->size == sizeof(player_laser_data_t));
     player_laser_data_t * l_data = reinterpret_cast<player_laser_data_t * > 
(data);
 
     UpdateLaser(l_data, hdr->timestamp);
@@ -426,14 +424,12 @@
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_PTZ_DATA_STATE, 
ptz_id))
   {
-    assert(hdr->size == sizeof(player_ptz_data_t));
     UpdatePtz(reinterpret_cast<player_ptz_data_t * > (data), hdr->timestamp);
     return 0;
   }
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, 
PLAYER_BLOBFINDER_DATA_BLOBS, blobfinder_id))
   {
-    assert(hdr->size == sizeof(player_blobfinder_data_t));
     UpdateBlobfinder(reinterpret_cast<player_blobfinder_data_t * > (data), 
hdr->timestamp);
     return 0;
   }

Modified: code/player/trunk/server/drivers/fiducial/laservisualbw.cc
===================================================================
--- code/player/trunk/server/drivers/fiducial/laservisualbw.cc  2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/fiducial/laservisualbw.cc  2008-12-18 
19:58:30 UTC (rev 7206)
@@ -394,11 +394,9 @@
 int LaserVisualBW::ProcessMessage (QueuePointer &resp_queue, player_msghdr * 
hdr, void * data)
 {
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_LASER_DATA_SCAN, 
laser_id))
   {
-    assert(hdr->size == sizeof(player_laser_data_t));
     player_laser_data_t * l_data = reinterpret_cast<player_laser_data_t * > 
(data);
 
     UpdateLaser(l_data, hdr->timestamp);
@@ -408,14 +406,12 @@
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_PTZ_DATA_STATE, 
ptz_id))
   {
-    assert(hdr->size == sizeof(player_ptz_data_t));
     UpdatePtz(reinterpret_cast<player_ptz_data_t * > (data), hdr->timestamp);
     return 0;
   }
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, 
PLAYER_CAMERA_DATA_STATE, camera_id))
   {
-    assert(hdr->size == sizeof(player_camera_data_t));
     UpdateCamera(reinterpret_cast<player_camera_data_t * > (data), 
hdr->timestamp);
     return 0;
   }

Modified: code/player/trunk/server/drivers/imu/XSensMT.cc
===================================================================
--- code/player/trunk/server/drivers/imu/XSensMT.cc     2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/imu/XSensMT.cc     2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -278,7 +278,6 @@
                              void * data)
 {
     assert (hdr);
-    assert (data);
 
     // this holds possible error messages returned by mtcomm.writeMessage
     int err;

Modified: code/player/trunk/server/drivers/imu/nimuplayer.cpp
===================================================================
--- code/player/trunk/server/drivers/imu/nimuplayer.cpp 2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/imu/nimuplayer.cpp 2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -249,7 +249,6 @@
                                                         void * data)
 {
        assert (hdr);
-       assert (data);
 
        return -1;
 }

Modified: code/player/trunk/server/drivers/laser/sicklms400.cc
===================================================================
--- code/player/trunk/server/drivers/laser/sicklms400.cc        2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/laser/sicklms400.cc        2008-12-18 
19:58:30 UTC (rev 7206)
@@ -391,7 +391,6 @@
                               void* data)
 {
   assert (hdr);
-//  assert (data);
 
   // ---[ Get geometry
   if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,

Modified: code/player/trunk/server/drivers/map/maptransform.cc
===================================================================
--- code/player/trunk/server/drivers/map/maptransform.cc        2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/map/maptransform.cc        2008-12-18 
19:58:30 UTC (rev 7206)
@@ -199,8 +199,6 @@
   PLAYER_MSG0(9,"ProcessMessage called for MapTransform Driver");
 
   assert(hdr);
-  // assert fails on empty messages
-  //assert(data);
  
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_MAP_REQ_GET_INFO, 
device_addr))
   {

Modified: code/player/trunk/server/drivers/mcom/lifomcom.cc
===================================================================
--- code/player/trunk/server/drivers/mcom/lifomcom.cc   2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/mcom/lifomcom.cc   2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -124,8 +124,6 @@
 int LifoMCom::ProcessMessage(ClientData * client, player_msghdr * hdr, uint8_t 
* data, uint8_t * resp_data, size_t * resp_len)
 {
   assert(hdr);
-  assert(data);
-  assert(resp_len);
   if (hdr->size < sizeof(player_mcom_config_t))
     return -1;
 

Modified: code/player/trunk/server/drivers/mixed/clodbuster/clodbuster.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/clodbuster/clodbuster.cc     
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/clodbuster/clodbuster.cc     
2008-12-18 19:58:30 UTC (rev 7206)
@@ -255,7 +255,6 @@
 {
 
   assert(hdr);
-  assert(data);
 
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, 
PLAYER_POSITION2D_REQ_SET_ODOM, device_addr))
   {

Modified: code/player/trunk/server/drivers/mixed/cmucam2/cmucam2.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/cmucam2/cmucam2.cc   2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/cmucam2/cmucam2.cc   2008-12-18 
19:58:30 UTC (rev 7206)
@@ -309,7 +309,6 @@
                                                                void * data)
 {
        assert(hdr);
-       assert(data);
 
        if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_PTZ_CMD_STATE, ptz_id))
        {

Modified: code/player/trunk/server/drivers/mixed/evolution/er1/er.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/evolution/er1/er.cc  2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/evolution/er1/er.cc  2008-12-18 
19:58:30 UTC (rev 7206)
@@ -790,7 +790,6 @@
                       void * data)
 {
   assert(hdr);
-  assert(data);
 
   if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, 
PLAYER_POSITION2D_REQ_GET_GEOM, position_id))
   {

Modified: code/player/trunk/server/drivers/mixed/garcia/garcia_mixed.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/garcia/garcia_mixed.cc       
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/garcia/garcia_mixed.cc       
2008-12-18 19:58:30 UTC (rev 7206)
@@ -357,9 +357,7 @@
                              player_msghdr* hdr,
                              void* data)
 {
-  assert(resp_queue);
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD,
                            PLAYER_POSITION2D_CMD_POS, mPos2dAddr))
@@ -378,14 +376,12 @@
   else if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD,
                                 PLAYER_SPEECH_CMD_SAY, mSpeechAddr))
   {
-    assert(hdr->size == sizeof(player_speech_cmd_t));
     ProcessSpeechCommand(hdr, *reinterpret_cast<player_speech_cmd_t *>(data));
     return(0);
   }
   else if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_DATA,
                                 PLAYER_DIO_CMD_VALUES, mDioAddr))
   {
-    assert(hdr->size == sizeof(player_dio_cmd_t));
     ProcessDioCommand(hdr, *reinterpret_cast<player_dio_cmd_t *>(data));
     return(0);
   }

Modified: code/player/trunk/server/drivers/mixed/khepera/khepera.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/khepera/khepera.cc   2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/khepera/khepera.cc   2008-12-18 
19:58:30 UTC (rev 7206)
@@ -162,7 +162,6 @@
 int Khepera::ProcessMessage(QueuePointer & resp_queue, player_msghdr * hdr, 
void * data)
 {
        assert(hdr);
-       assert(data);
 
        if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_IR_REQ_POSE, 
ir_addr))
        {

Modified: code/player/trunk/server/drivers/mixed/reb/reb.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/reb/reb.cc   2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/mixed/reb/reb.cc   2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -738,9 +738,6 @@
 int REB::ProcessMessage(ClientData * client, player_msghdr * hdr, uint8_t * 
data, uint8_t * resp_data, size_t * resp_len)
 {
   assert(hdr);
-  assert(data);
-  assert(resp_data);
-  assert(resp_len);
 
   if (MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 0, position_id))
   {
@@ -752,7 +749,6 @@
 
   if (MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_IR_REQ_POWER, ir_id))
   {
-       assert(hdr->size == sizeof(player_ir_power_req_t));
        player_ir_power_req_t * powreq = reinterpret_cast<player_ir_power_req_t 
*> (data);
 
     if (powreq->state)
@@ -766,7 +762,6 @@
 
   if (MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_IR_REQ_POSE, ir_id))
   {
-       assert(*resp_len >= sizeof(player_ir_pose_t));
        player_ir_pose_t & irpose = *reinterpret_cast<player_ir_pose_t *> 
(resp_data);
 
     uint16_t numir = PlayerUBotRobotParams[param_index].NumberIRSensors;

Modified: code/player/trunk/server/drivers/mixed/sr3000/sr3000.cc
===================================================================
--- code/player/trunk/server/drivers/mixed/sr3000/sr3000.cc     2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/mixed/sr3000/sr3000.cc     2008-12-18 
19:58:30 UTC (rev 7206)
@@ -429,7 +429,6 @@
                             void * data)
 {
   assert (hdr);
-  assert (data);
 
   if (provideStereo)
     ProcessMessageCamera (resp_queue, hdr, data, stereo_addr);

Modified: code/player/trunk/server/drivers/position/ascension/flockofbirds.cc
===================================================================
--- code/player/trunk/server/drivers/position/ascension/flockofbirds.cc 
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/ascension/flockofbirds.cc 
2008-12-18 19:58:30 UTC (rev 7206)
@@ -492,9 +492,6 @@
 
 int FlockOfBirds_Device::ProcessMessage(QueuePointer & resp_queue, 
player_msghdr * hdr, void * data)
 {
-  assert(hdr);
-  assert(data);
-
   return -1;
 }
 

Modified: code/player/trunk/server/drivers/position/bumpersafe/bumpersafe.cc
===================================================================
--- code/player/trunk/server/drivers/position/bumpersafe/bumpersafe.cc  
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/bumpersafe/bumpersafe.cc  
2008-12-18 19:58:30 UTC (rev 7206)
@@ -161,7 +161,6 @@
                                void * data)
 {
   assert(hdr);
-  assert(data);
 
   if (hdr->type==PLAYER_MSGTYPE_SYNCH)
   {

Modified: code/player/trunk/server/drivers/position/isense/inertiacube2.cc
===================================================================
--- code/player/trunk/server/drivers/position/isense/inertiacube2.cc    
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/isense/inertiacube2.cc    
2008-12-18 19:58:30 UTC (rev 7206)
@@ -454,7 +454,6 @@
 int InertiaCube2::ProcessMessage (QueuePointer &resp_queue, player_msghdr * 
hdr, void * data)
 {
   assert(hdr);
-  assert(data);
 
   if(Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA , 
PLAYER_POSITION2D_DATA_STATE, position_id))
   {

Modified: code/player/trunk/server/drivers/position/lasersafe/lasersafe.cc
===================================================================
--- code/player/trunk/server/drivers/position/lasersafe/lasersafe.cc    
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/lasersafe/lasersafe.cc    
2008-12-18 19:58:30 UTC (rev 7206)
@@ -274,8 +274,6 @@
 int LaserSafe::ProcessMessage (QueuePointer & resp_queue, player_msghdr * hdr, 
void * data)
 {
   assert(hdr);
-  assert(data);
-
   if (hdr->type==PLAYER_MSGTYPE_SYNCH)
   {
     return 0;

Modified: code/player/trunk/server/drivers/position/mbicp/mbicp_driver.cc
===================================================================
--- code/player/trunk/server/drivers/position/mbicp/mbicp_driver.cc     
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/mbicp/mbicp_driver.cc     
2008-12-18 19:58:30 UTC (rev 7206)
@@ -7,7 +7,7 @@
 
 J. Minguez, L. Montesano, and F. Lamiraux, "Metric-based iterative
 closest point scan matching for sensor displacement estimation," IEEE
-Transactions on Robotics, vol. 22, no. 5, pp. 1047 \u2013 1054, 2006. 
+Transactions on Robotics, vol. 22, no. 5, pp. 1047 \u2013 1054, 2006.
 
 @par Compile-time dependencies
 
@@ -20,7 +20,7 @@
 @par Requires
 
 - @ref interface_position2d : source of pose and velocity information
-- @ref interface_laser : Pose-stamped laser scans (subtype 
+- @ref interface_laser : Pose-stamped laser scans (subtype
 PLAYER_LASER_DATA_SCANPOSE)
 
 @par Configuration requests
@@ -30,111 +30,111 @@
 @par Configuration file options
 
 - max_laser_range (float)
-  - Default: 7.9 m    
+  - Default: 7.9 m
   - Maximum laser range.
 
 - laserPose_x (float)
-  - Default: 0.16 m    
+  - Default: 0.16 m
   - Offset of the laser on the edge x (in the robot's system of reference).
 
 - laserPose_y (float)
-  - Default: 0.0 m    
+  - Default: 0.0 m
   - Offset of the laser on the edge y (in the robot's system of reference).
-  
+
 - laserPose_th (float)
-  - Default: 0.0 rad    
+  - Default: 0.0 rad
   - Offset of the laser on th (in the robot's system of reference).
 
 - radial_window        (float)
-  - Default: 0.3 m    
-  - Maximum distance difference between points of different scans. Points 
+  - Default: 0.3 m
+  - Maximum distance difference between points of different scans. Points
     with greater Br cannot be correspondent (eliminate spurius asoc.).
- 
+
 - angular_window (float)
   - Default: 0.523333333 rad
-  - Maximum angle diference between points of different scans. Points 
-    with greater Bw cannot be correspondent (eliminate spurius asoc.). 
-  
+  - Maximum angle diference between points of different scans. Points
+    with greater Bw cannot be correspondent (eliminate spurius asoc.).
+
 - L (float)
-  - Default: 3.00   
-  - Value of the metric. When L tends to infinity you are using the 
-    standart ICP. When L tends to 0 you use the metric (more importance 
+  - Default: 3.00
+  - Value of the metric. When L tends to infinity you are using the
+    standart ICP. When L tends to 0 you use the metric (more importance
     to rotation), when L tends to infinity you are using Euclidian metric.
 
 - laserStep (integer)
-  - Default: 1   
+  - Default: 1
   - Selects points of each scan with an step laserStep.
     When laserStep=1 uses all the points of the scans
-    When laserStep=2 uses one each two ... 
-    This is an speed up parameter. 
-    
+    When laserStep=2 uses one each two ...
+    This is an speed up parameter.
+
 - MaxDistInter (float)
-  - Default: 0.5 m   
-  - Maximum distance to interpolate between points in the ref scan. 
Consecutive 
-    points with less Euclidean distance than MaxDistInter are considered 
+  - Default: 0.5 m
+  - Maximum distance to interpolate between points in the ref scan. Consecutive
+    points with less Euclidean distance than MaxDistInter are considered
     to be a segment.
 
 - filter (float)
-  - Default: 0.95   
-  - In [0,1] sets the % of asociations NOT considered spurious. E.g. if 
-    filter=0.9 you use 90% of the associations. The associations 
-    are ordered by distance and the (1-filter) with greater distance 
+  - Default: 0.95
+  - In [0,1] sets the % of asociations NOT considered spurious. E.g. if
+    filter=0.9 you use 90% of the associations. The associations
+    are ordered by distance and the (1-filter) with greater distance
     are not used. This type of filtering is called "trimmed-ICP".
-    
+
 - ProjectionFilter (int)
-  - Default: 1   
-  - Eliminate the points that cannot be seen given the two scans 
-    (see Lu&Millios 97). It works well for angles < 45 deg. 
+  - Default: 1
+  - Eliminate the points that cannot be seen given the two scans
+    (see Lu&Millios 97). It works well for angles < 45 deg.
     1 : activates the filter.
     0 : desactivates the filter.
 
 - AsocError (float)
-  - Default: 0.1   
+  - Default: 0.1
   - In [0,1]. Sets the % of minimun associations to run the algorithm.
-    One way to check if the algorithm diverges is to supervise 
-    if the number of associatios goes below a thresold. When the number 
+    One way to check if the algorithm diverges is to supervise
+    if the number of associatios goes below a thresold. When the number
     of associations is below AsocError, the main function will return
     error in associations step.
- 
+
 - MaxIter (int)
-  - Default: 50   
-  - Sets the maximum number of iterations for the algorithm to exit. The 
+  - Default: 50
+  - Sets the maximum number of iterations for the algorithm to exit. The
     more iterations, the more chance you give the algorithm to be more 
accurate.
 
 - errorRatio (float)
   - Default: 0.0001 m
-  - In [0,1] sets the maximum error ratio between iterations to exit. In 
-    iteration K, let be errorK the residual of the minimization. 
-    Error_th=(errorK-1/errorK). When error_th tends to 1 more precise is 
+  - In [0,1] sets the maximum error ratio between iterations to exit. In
+    iteration K, let be errorK the residual of the minimization.
+    Error_th=(errorK-1/errorK). When error_th tends to 1 more precise is
     the solution of the scan matching.
 
 - IterSmoothConv (int)
-  - Default: 2   
-  - Number of consecutive iterations that satisfity the error criteria 
+  - Default: 2
+  - Number of consecutive iterations that satisfity the error criteria
     (the two above criteria) (error_th) OR (errorx_out && errory_out && 
errt_out).
-    With this parameter >1 avoids random solutions and estabilices the 
algorithm. 
+    With this parameter >1 avoids random solutions and estabilices the 
algorithm.
 
 - errx_out (float)
-  - Default: 0.0001 m   
-  - Minimum error in x of the asociations to exit. In each iteration, the 
error 
-    is the residual of the minimization in each component. The condition is 
-    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK 
+  - Default: 0.0001 m
+  - Minimum error in x of the asociations to exit. In each iteration, the error
+    is the residual of the minimization in each component. The condition is
+    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK
     tends to 0 the more precise is the solution of the scan matching
-    
+
 - erry_out (float)
-  - Default: 0.0001 m   
-  - Minimum error in x of the asociations to exit. In each iteration, the 
error 
-    is the residual of the minimization in each component. The condition is 
-    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK 
+  - Default: 0.0001 m
+  - Minimum error in x of the asociations to exit. In each iteration, the error
+    is the residual of the minimization in each component. The condition is
+    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK
     tends to 0 the more precise is the solution of the scan matching
 
 - errt_out (float)
-  - Default: 0.0001 m   
-  - Minimum error in x of the asociations to exit. In each iteration, the 
error 
-    is the residual of the minimization in each component. The condition is 
-    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK 
+  - Default: 0.0001 m
+  - Minimum error in x of the asociations to exit. In each iteration, the error
+    is the residual of the minimization in each component. The condition is
+    (errorKx<errx_out && errorKx<erry_out && errorKx<errt_out). When errorK
     tends to 0 the more precise is the solution of the scan matching
-    
+
 @par Example
 
 @verbatim
@@ -148,23 +148,23 @@
   laserPose_x                  0.16
   laserPose_y                  0
   laserPose_th                 0
-  
-  radial_window                0.3    
-  angular_window               0.523333333     
-  
-  L                            3.00    
-  laserStep                    1       
-  MaxDistInter                 0.5     
-  filter                       0.95    
-  ProjectionFilter             1       
-  AsocError                    0.1     
-  MaxIter                      50      
-  
-  errorRatio                   0.0001  
-  errx_out                     0.0001  
-  erry_out                     0.0001  
-  errt_out                     0.0001  
-  IterSmoothConv               2       
+
+  radial_window                0.3
+  angular_window               0.523333333
+
+  L                            3.00
+  laserStep                    1
+  MaxDistInter                 0.5
+  filter                       0.95
+  ProjectionFilter             1
+  AsocError                    0.1
+  MaxIter                      50
+
+  errorRatio                   0.0001
+  errx_out                     0.0001
+  erry_out                     0.0001
+  errt_out                     0.0001
+  IterSmoothConv               2
 )
 
 @endverbatim
@@ -185,7 +185,7 @@
 {
 
 public:
-    
+
     mbicp( ConfigFile* cf, int section);
     virtual ~mbicp();
 
@@ -213,7 +213,7 @@
        float   errt_out;
        int     IterSmoothConv;
        Tsc     laserPoseTsc;
- 
+
        player_pose2d_t         lastPoseOdom,
                                currentPose,
                                previousPose,
@@ -221,7 +221,7 @@
 
        player_laser_data_t     currentScan,
                                previousScan;
-                               
+
        bool            havePrevious;
 
        //Compute scanMatching
@@ -300,21 +300,21 @@
 
////////////////////////////////////////////////////////////////////////////////
 void mbicp::setupScanMatching(){
 
-Init_MbICP_ScanMatching( 
+Init_MbICP_ScanMatching(
                        this->max_laser_range,
-                       this->Bw,        
-                       this->Br,        
-                       this->L,         
+                       this->Bw,
+                       this->Br,
+                       this->L,
                        this->laserStep,
                        this->MaxDistInter,
-                       this->filter,    
+                       this->filter,
                        this->ProjectionFilter,
                        this->AsocError,
-                       this->MaxIter,  
+                       this->MaxIter,
                        this->errorRatio,
-                       this->errx_out, 
-                       this->erry_out,  
-                       this->errt_out,  
+                       this->errx_out,
+                       this->erry_out,
+                       this->errt_out,
                        this->IterSmoothConv);
 }
 
@@ -420,7 +420,7 @@
    cmd.vel.px = 0;
    cmd.vel.py = 0;
    cmd.vel.pa = 0;
- 
+
    odom->PutMsg(InQueue, PLAYER_MSGTYPE_CMD, PLAYER_POSITION2D_CMD_VEL,
                 (void*)&cmd,sizeof(cmd),NULL);
 
@@ -436,7 +436,7 @@
        while (true){
                // Wait till we get new data
                Wait();
-               
+
                // Test if we are supposed to cancel this thread.
                pthread_testcancel();
 
@@ -452,7 +452,6 @@
        // PLAYER_LASER_DATA_SCANPOSE
        if(Message::MatchMessage(hdr, 
PLAYER_MSGTYPE_DATA,PLAYER_LASER_DATA_SCANPOSE, laser_addr))
        {
-               assert(hdr->size == sizeof(player_laser_data_scanpose_t));
                ProcessSubtypeLaser(hdr, 
*reinterpret_cast<player_laser_data_scanpose_t *> (data));
        }else
 
@@ -469,7 +468,7 @@
                player_msghdr_t newhdr = *hdr;
                newhdr.addr = device_addr;
                Publish(&newhdr, (void*)&data);
-       }else 
+       }else
 
        if(Message::MatchMessage(hdr, 
PLAYER_MSGTYPE_CMD,/*PLAYER_POSITION2D_CMD_VEL*/ -1, device_addr))
        {
@@ -479,7 +478,7 @@
                newhdr.addr = odom_addr;
                odom->PutMsg(InQueue, &newhdr, (void*)data);
        }else
-       { 
+       {
                if(Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, -1, 
device_addr)){
                        // Pass the request on to the underlying position 
device and wait for
                        // the reply.
@@ -505,14 +504,14 @@
 void mbicp::ProcessOdom(player_msghdr_t* hdr,player_position2d_data_t &data)
 {
 
-       
+
        Tsc     outComposicion1,
                outComposicion2,
                outInversion1;
-                       
+
        Tsc     lastPoseOdomTsc,
                previousPoseTsc,
-               scanmatchingPoseTsc;            
+               scanmatchingPoseTsc;
 
 
        lastPoseOdom.px = data.pos.px;
@@ -528,15 +527,15 @@
                inversion_sis(&previousPoseTsc, &outInversion1);
                composicion_sis(&outInversion1, &lastPoseOdomTsc, 
&outComposicion1);
                composicion_sis(&scanmatchingPoseTsc, &outComposicion1, 
&outComposicion2);
-       
 
+
                data.pos.px     = outComposicion2.x;
                data.pos.py     = outComposicion2.y;
                data.pos.pa     = outComposicion2.tita;
 
 
-       }       
-       
+       }
+
        player_msghdr_t newhdr = *hdr;
        newhdr.addr = device_addr;
        Publish(&newhdr, (void*)&data);
@@ -552,20 +551,20 @@
 
        currentPose     = lastPoseOdom;
 
-       currentScan.min_angle           = data.scan.min_angle;          
-       currentScan.max_angle           = data.scan.max_angle;  
+       currentScan.min_angle           = data.scan.min_angle;
+       currentScan.max_angle           = data.scan.max_angle;
        currentScan.resolution          = data.scan.resolution;
-       currentScan.max_range           = data.scan.max_range;  
+       currentScan.max_range           = data.scan.max_range;
        currentScan.ranges_count        = data.scan.ranges_count;
-       currentScan.intensity_count     = data.scan.intensity_count;    
+       currentScan.intensity_count     = data.scan.intensity_count;
        currentScan.id                                  = data.scan.id;
-       
+
        for (unsigned int i=0; i < currentScan.ranges_count; i++){
                currentScan.ranges[i] = data.scan.ranges[i];
                currentScan.intensity[i] = data.scan.intensity[i];
        }
 
-       if (havePrevious && (   currentPose.px != previousPose.px || 
+       if (havePrevious && (   currentPose.px != previousPose.px ||
                                currentPose.py != previousPose.py ||
                                currentPose.pa != previousPose.pa))
        {
@@ -578,7 +577,7 @@
                previousPose            = currentPose;
                scanmatchingPose        = currentPose;
                havePrevious            = true;
-       }                                       
+       }
 }
 
 
@@ -589,7 +588,7 @@
                currentPoseTsc,
                scanmatchingPoseTsc,
                solutionTsc;
-       
+
        Tsc     outComposicion1,
                outComposicion2,
                outComposicion3,
@@ -598,13 +597,13 @@
                outComposicion11,
                outInversion1,
                outInversion4;
-                       
+
        Tpfp    previousScanTpfp[LASER_MAX_SAMPLES],
                currentScanTpfp[LASER_MAX_SAMPLES];
-                       
-       int     salidaMbicp;            
-                       
 
+       int     salidaMbicp;
+
+
        currentPoseTsc          = playerPose2Tsc(currentPose);
        previousPoseTsc         = playerPose2Tsc(previousPose);
        scanmatchingPoseTsc     = playerPose2Tsc(scanmatchingPose);
@@ -618,7 +617,7 @@
        playerLaser2Tpfp(previousScan,previousScanTpfp);
        playerLaser2Tpfp(currentScan,currentScanTpfp);
 
-       salidaMbicp = 
MbICPmatcher(previousScanTpfp,currentScanTpfp,&outComposicion3, &solutionTsc);  
  
+       salidaMbicp = 
MbICPmatcher(previousScanTpfp,currentScanTpfp,&outComposicion3, &solutionTsc);
 
        if (salidaMbicp == 1){
 
@@ -635,7 +634,7 @@
        else{
 
                if (salidaMbicp == 2)
-                       fprintf(stderr,"2 : Everything OK but reached the 
Maximum number of iterations\n");             
+                       fprintf(stderr,"2 : Everything OK but reached the 
Maximum number of iterations\n");
                else{
                        if (salidaMbicp == -1)
                                fprintf(stderr,"Failure in the association 
step\n");
@@ -663,7 +662,7 @@
 Tsc mbicp::playerPose2Tsc(player_pose2d_t posicion)
 {
        Tsc     posicionTsc;
-       
+
        posicionTsc.x = posicion.px;
        posicionTsc.y = posicion.py;
        posicionTsc.tita = posicion.pa;
@@ -675,7 +674,7 @@
 player_pose2d_t mbicp::Tsc2playerPose(Tsc posicion)
 {
        player_pose2d_t posicionPlayer;
-       
+
        posicionPlayer.px = posicion.x;
        posicionPlayer.py = posicion.y;
        posicionPlayer.pa = posicion.tita;

Modified: code/player/trunk/server/drivers/position/roboteq/roboteq.cc
===================================================================
--- code/player/trunk/server/drivers/position/roboteq/roboteq.cc        
2008-12-18 19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/position/roboteq/roboteq.cc        
2008-12-18 19:58:30 UTC (rev 7206)
@@ -23,7 +23,7 @@
 /** @{ */
 /** @defgroup driver_roboteq roboteq
  * @brief Motor control driver for Roboteq AX2550
- 
+
 Provides position2d interface to the Roboteq AX2550 motor controller
 http://www.roboteq.com/ax2550-folder.html
 This driver ignores all configuration requests and produces no data
@@ -77,7 +77,7 @@
 driver
 (
   name "roboteq"
-  provides ["position2d:0"] 
+  provides ["position2d:0"]
   devicepath "/dev/ttyS0"
   max_trans_spd 6.0
   max_rot_spd 4.0
@@ -95,15 +95,15 @@
 #include <termios.h>
 #include <sys/ioctl.h> // ioctl
 #include <unistd.h> // close(2),fcntl(2),getpid(2),usleep(3),execvp(3),fork(2)
-#include <netdb.h> // for gethostbyname(3) 
-#include <netinet/in.h>  // for struct sockaddr_in, htons(3) 
-#include <sys/types.h>  // for socket(2) 
-#include <sys/socket.h>  // for socket(2) 
-#include <signal.h>  // for kill(2) 
-#include <fcntl.h>  // for fcntl(2) 
-#include <string.h>  // for strncpy(3),memcpy(3) 
-#include <stdlib.h>  // for atexit(3),atoi(3) 
-#include <pthread.h>  // for pthread stuff 
+#include <netdb.h> // for gethostbyname(3)
+#include <netinet/in.h>  // for struct sockaddr_in, htons(3)
+#include <sys/types.h>  // for socket(2)
+#include <sys/socket.h>  // for socket(2)
+#include <signal.h>  // for kill(2)
+#include <fcntl.h>  // for fcntl(2)
+#include <string.h>  // for strncpy(3),memcpy(3)
+#include <stdlib.h>  // for atexit(3),atoi(3)
+#include <pthread.h>  // for pthread stuff
 #include <math.h>
 
 #include <libplayercore/playercore.h>
@@ -112,7 +112,7 @@
 #define SERIAL_BUFF_SIZE               128
 #define MAX_MOTOR_SPEED                        127
 #define ROBOTEQ_CON_TIMEOUT            10      // seconds to time-out on 
setting RS-232 mode
-#define ROBOTEQ_DEFAULT_BAUD   9600 
+#define ROBOTEQ_DEFAULT_BAUD   9600
 
 #ifndef CRTSCTS
 #ifdef IHFLOW
@@ -165,8 +165,8 @@
 
   public:
     roboteq( ConfigFile* cf, int section);
-    
-    virtual int ProcessMessage(QueuePointer &resp_queue, 
+
+    virtual int ProcessMessage(QueuePointer &resp_queue,
                                                player_msghdr * hdr, void * 
data);
     virtual int Setup();
     virtual int Shutdown();
@@ -191,7 +191,7 @@
 
 ///////////////////////////////////////////////////////////////////////////
 roboteq::roboteq( ConfigFile* cf, int section) : Driver(cf, section)
-{  
+{
        memset (&this->position2d_id, 0, sizeof (player_devaddr_t));
 
     // Outgoing position 2d interface
@@ -199,12 +199,12 @@
                       PLAYER_POSITION2D_CODE, -1, NULL) == 0){
                if(this->AddInterface(this->position2d_id) != 0){
                        this->SetError(-1);
-                       return;         
+                       return;
        }   }
 
     double max_trans_spd, max_rot_spd;
 
-  // required parameter(s)   
+  // required parameter(s)
   if(!(this->devicepath = (char*)cf->ReadString(section, "devicepath", NULL))){
     PLAYER_ERROR("must specify devicepath");
     this->SetError(-1);
@@ -244,10 +244,10 @@
   roboteq_fd = open(devicepath, O_RDWR|O_NDELAY);
   if (roboteq_fd == -1){
     fputs("Unable to configure serial port for RoboteQ!", stderr);
-    return 0; 
+    return 0;
   }else{
       struct termios options;
-      
+
       tcgetattr(roboteq_fd, &options);
 
       // default is 9600 unless otherwise specified
@@ -287,7 +287,7 @@
 
   // initialize RoboteQ to RS-232 mode
   strcpy(serialout_buff, "\r");
-  for (i=0; i<10; i++){ 
+  for (i=0; i<10; i++){
     write(roboteq_fd, serialout_buff, 1);
     tcdrain(roboteq_fd);
        usleep(25000);
@@ -311,9 +311,9 @@
        else
                fputs("Successfully initialized Roboteq connection.\n", stderr);
 
-       fputs("Done.\n", stderr); 
+       fputs("Done.\n", stderr);
 
-  // now spawn reading thread 
+  // now spawn reading thread
   StartThread();
 
   return(0);
@@ -346,11 +346,11 @@
                        // no 'W's for ROBOTEQ_CON_TIMEOUT seconds
                        //              means we're probably in RC mode again
 
-                       // 07-09-07 
+                       // 07-09-07
                        // this test may need to change since the reset
                        // appears to fail quite often. is it really
                        // failing or is the test bad?
-                       return 0; 
+                       return 0;
                }
                memset(serialin_buff, 0, SERIAL_BUFF_SIZE);
                ret = read(roboteq_fd, serialin_buff, SERIAL_BUFF_SIZE);
@@ -358,7 +358,7 @@
        fputs("Unable to reset Roboteq to RC mode!", stderr);
 
     close(roboteq_fd);
-  
+
   return(0);
 }
 
@@ -368,22 +368,21 @@
 int roboteq::ProcessMessage (QueuePointer &resp_queue, player_msghdr * hdr, 
void * data)
 {
     assert(hdr);
-       assert(data);
 /*
-    fprintf(stderr, "ProcessMessage: type=%d subtype=%d\n", 
+    fprintf(stderr, "ProcessMessage: type=%d subtype=%d\n",
             hdr->type, hdr->subtype);
-  */      
-       if (Message::MatchMessage(hdr, PLAYER_POSITION2D_REQ_MOTOR_POWER, 
-                                PLAYER_POSITION2D_CMD_VEL, position2d_id)){    
     
+  */
+       if (Message::MatchMessage(hdr, PLAYER_POSITION2D_REQ_MOTOR_POWER,
+                                PLAYER_POSITION2D_CMD_VEL, position2d_id)){
         assert(hdr->size == sizeof(player_position2d_cmd_vel_t));
 
-        player_position2d_cmd_vel_t & command 
+        player_position2d_cmd_vel_t & command
             = *reinterpret_cast<player_position2d_cmd_vel_t *> (data);
-        
+
         // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
-        // convert from the generic position interface 
+        // convert from the generic position interface
         // to the Roboteq-specific command
-        // assumes "Mixed Mode" -- 
+        // assumes "Mixed Mode" --
         // channel 1 : FW/BW speed
         // channel 2 : rotation
         // ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
@@ -392,7 +391,7 @@
         float vel_yawspd = command.vel.pa;
 
         //fprintf(stderr, "ProcessMessage: trans=%f, steer=%f\n", vel_trans, 
vel_turret);
-        
+
         // scale and translate to Roboteq command
         vel_xtrans = (double)vel_xtrans * speed_scaling_factor;
         vel_yawspd = (double)vel_yawspd * rot_scaling_factor;
@@ -409,7 +408,7 @@
         */
         return 0;
     }
-      
+
   return -1;
 }
 
@@ -419,20 +418,20 @@
 void roboteq::Main()
 {
   double position_time=0;
-    
+
   pthread_setcanceltype(PTHREAD_CANCEL_DEFERRED,NULL);
 
   for(;;){
     ProcessMessages();
        pthread_testcancel();
     // publish dummy data
-    Publish(device_addr, PLAYER_MSGTYPE_DATA, PLAYER_POSITION2D_DATA_STATE, 
+    Publish(device_addr, PLAYER_MSGTYPE_DATA, PLAYER_POSITION2D_DATA_STATE,
                          (unsigned char*) &data, sizeof(data), &position_time);
     usleep(10);
   }
 
   pthread_exit(NULL);
-  
+
   return;
 }
 
@@ -447,22 +446,22 @@
   else if (trans_command < -MAX_MOTOR_SPEED) trans_command = -MAX_MOTOR_SPEED;
   if (rot_command > MAX_MOTOR_SPEED) rot_command = MAX_MOTOR_SPEED;
   else if (rot_command < -MAX_MOTOR_SPEED) rot_command = -MAX_MOTOR_SPEED;
-  
+
   if (trans_command > 0)
     strcpy(speed, FORWARD);
   else strcpy(speed, REVERSE);
   if (rot_command > 0)
     strcpy(heading, LEFT);
   else strcpy(heading, RIGHT);
-  
+
   // form motor cmd string
   strcpy(cmd_str, speed);
   snprintf(cmd_str+2, 4, "%.2x", abs(trans_command)); // start at char 3
-  strcat(cmd_str, "\r");       
+  strcat(cmd_str, "\r");
   strcat(cmd_str, heading);
   snprintf(cmd_str + strlen(cmd_str), 4, "%.2x", abs(rot_command));
   strcat(cmd_str, "\r");
-  
+
   return 0;
 }
 

Modified: code/player/trunk/server/drivers/ptz/amtecpowercube.cc
===================================================================
--- code/player/trunk/server/drivers/ptz/amtecpowercube.cc      2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/ptz/amtecpowercube.cc      2008-12-18 
19:58:30 UTC (rev 7206)
@@ -999,7 +999,6 @@
 int AmtecPowerCube::ProcessMessage(QueuePointer &resp_queue, player_msghdr * 
hdr, void * data)
 {
   assert(hdr);
-  assert(data);
 
        if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_PTZ_CMD_STATE, device_addr))
        {

Modified: code/player/trunk/server/drivers/ptz/canonvcc4.cc
===================================================================
--- code/player/trunk/server/drivers/ptz/canonvcc4.cc   2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/ptz/canonvcc4.cc   2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -949,7 +949,6 @@
 int canonvcc4::ProcessMessage(QueuePointer &resp_queue, player_msghdr * hdr, 
void * data)
 {
   assert(hdr);
-  assert(data);
 
   if (Message::MatchMessage(hdr,
                            PLAYER_MSGTYPE_REQ,

Modified: code/player/trunk/server/drivers/ptz/ptu46.cc
===================================================================
--- code/player/trunk/server/drivers/ptz/ptu46.cc       2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/ptz/ptu46.cc       2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -632,7 +632,6 @@
 PTU46_Device::ProcessMessage (QueuePointer &resp_queue, player_msghdr * hdr, 
void * data)
 {
     assert (hdr);
-    assert (data);
 
     // No REQ_GENERIC
     if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ, 
PLAYER_PTZ_REQ_GENERIC, device_addr))

Modified: code/player/trunk/server/drivers/ptz/sonyevid30.cc
===================================================================
--- code/player/trunk/server/drivers/ptz/sonyevid30.cc  2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/ptz/sonyevid30.cc  2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -1377,7 +1377,6 @@
                                                           player_msghdr * hdr, 
void *data)
 {
   assert(hdr);
-  assert(data);
 
        if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ,
                                                        PLAYER_PTZ_REQ_GENERIC, 
device_addr)) {

Modified: code/player/trunk/server/drivers/rfid/sickrfi341.cc
===================================================================
--- code/player/trunk/server/drivers/rfid/sickrfi341.cc 2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/rfid/sickrfi341.cc 2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -203,9 +203,6 @@
                               player_msghdr* hdr,
                               void* data)
 {
-  assert (hdr);
-  assert (data);
-
   return (-1);
 }
 

Modified: code/player/trunk/server/drivers/speech/festival.cc
===================================================================
--- code/player/trunk/server/drivers/speech/festival.cc 2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/speech/festival.cc 2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -402,9 +402,6 @@
 
 int Festival::ProcessMessage(QueuePointer & resp_queue, player_msghdr * hdr, 
void * data)
 {
-       assert(hdr);
-       assert(data);
-
        if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_CMD, 
PLAYER_SPEECH_CMD_SAY, device_addr))
        {
                player_speech_cmd_t * cmd = (player_speech_cmd_t *) data;

Modified: code/player/trunk/server/drivers/vectormap/CMakeLists.txt
===================================================================
--- code/player/trunk/server/drivers/vectormap/CMakeLists.txt   2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/vectormap/CMakeLists.txt   2008-12-18 
19:58:30 UTC (rev 7206)
@@ -9,4 +9,4 @@
 
 PLAYERDRIVER_OPTION (vec2map build_vec2map ON)
 PLAYERDRIVER_REQUIRE_HEADER (vec2map build_vec2map geos_c.h)
-PLAYERDRIVER_ADD_DRIVER (postgis build_postgis LINKFLAGS "-lgeos" SOURCES 
vec2map.cc)
+PLAYERDRIVER_ADD_DRIVER (vec2map build_vec2map LINKFLAGS "-lgeos" SOURCES 
vec2map.cc)

Modified: code/player/trunk/server/drivers/vectormap/vec2map.cc
===================================================================
--- code/player/trunk/server/drivers/vectormap/vec2map.cc       2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/vectormap/vec2map.cc       2008-12-18 
19:58:30 UTC (rev 7206)
@@ -1,6 +1,6 @@
 /*
  *  Player - One Hell of a Robot Server
- *  Copyright (C) 2004  Brian Gerkey ger...@stanford.edu    
+ *  Copyright (C) 2004  Brian Gerkey ger...@stanford.edu
  *
  *  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
@@ -57,7 +57,7 @@
   - Default: ""
   - Do not draw feature with that name on final grid map
 
-...@par Example 
+...@par Example
 
 @verbatim
 driver
@@ -103,7 +103,7 @@
 
 class Vec2Map : public Driver
 {
-  public:    
+  public:
     // Constructor; need that
     Vec2Map(ConfigFile * cf, int section);
 
@@ -114,7 +114,7 @@
     virtual int Shutdown();
 
     // This method will be invoked on each incoming message
-    virtual int ProcessMessage(QueuePointer & resp_queue, 
+    virtual int ProcessMessage(QueuePointer & resp_queue,
                                player_msghdr * hdr,
                                void * data);
 
@@ -223,7 +223,7 @@
 
////////////////////////////////////////////////////////////////////////////////
 // Set up the device.  Return 0 if things go well, and -1 otherwise.
 int Vec2Map::Setup()
-{  
+{
   // Retrieve the handle to the vectormap device.
   this->vectormap_dev = deviceTable->GetDevice(this->vectormap_addr);
   if (!(this->vectormap_dev))
@@ -251,7 +251,7 @@
 {
   // Stop and join the driver thread
   StopThread();
-    
+
   // Unsubscribe from the vectormap
   this->vectormap_dev->Unsubscribe(this->InQueue);
 
@@ -260,7 +260,7 @@
 
 
////////////////////////////////////////////////////////////////////////////////
 // Main function for device thread
-void Vec2Map::Main() 
+void Vec2Map::Main()
 {
   struct timespec tspec;
 
@@ -271,7 +271,7 @@
     this->InQueue->Wait();
 
     pthread_testcancel();
-    
+
     // Process incoming messages
     ProcessMessages();
 
@@ -411,10 +411,10 @@
        if (over(static_cast<int>(x), 0, width)) break;
        if (over(static_cast<int>(y), 0, height)) break;
        cells[(static_cast<int>(y) * width) + (static_cast<int>(x))] = 1;
-    } 
+    }
 }
 
-int Vec2Map::ProcessMessage(QueuePointer & resp_queue, 
+int Vec2Map::ProcessMessage(QueuePointer & resp_queue,
                             player_msghdr * hdr,
                             void * data)
 {
@@ -768,7 +768,7 @@
 // that it can be invoked without object context.  In this function, we add
 // the driver into the given driver table, indicating which interface the
 // driver can support and how to create a driver instance.
-void Vec2Map_Register(DriverTable * table)
+void vec2map_Register(DriverTable * table)
 {
   table->AddDriver("vec2map", Vec2Map_Init);
 }

Modified: code/player/trunk/server/drivers/wifi/linuxwifi.cc
===================================================================
--- code/player/trunk/server/drivers/wifi/linuxwifi.cc  2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/wifi/linuxwifi.cc  2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -274,9 +274,6 @@
 
 int LinuxWiFi::ProcessMessage(QueuePointer & resp_queue, player_msghdr * hdr, 
void * data)
 {
-       assert(hdr);
-       assert(data);
-
        if (Message::MatchMessage(hdr, PLAYER_MSGTYPE_REQ, PLAYER_WIFI_REQ_MAC, 
device_addr))
        {
                player_wifi_mac_req_t req;

Modified: code/player/trunk/server/drivers/wsn/accel_calib.cc
===================================================================
--- code/player/trunk/server/drivers/wsn/accel_calib.cc 2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/wsn/accel_calib.cc 2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -297,9 +297,6 @@
     player_wsn_data_t  new_wsn_data;
     player_wsn_data_t* original_wsn_data;
 
-    assert (hdr);
-    assert (data);
-
     // Handle new data from the WSN device
     if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_DATA, PLAYER_WSN_DATA_STATE,
        wsn_addr))

Modified: code/player/trunk/server/drivers/wsn/mica2.cc
===================================================================
--- code/player/trunk/server/drivers/wsn/mica2.cc       2008-12-18 19:43:37 UTC 
(rev 7205)
+++ code/player/trunk/server/drivers/wsn/mica2.cc       2008-12-18 19:58:30 UTC 
(rev 7206)
@@ -474,9 +474,6 @@
                           player_msghdr * hdr,
                           void * data)
 {
-    assert (hdr);
-    assert (data);
-
     if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_CMD,
        PLAYER_WSN_CMD_DEVSTATE, wsn_addr))
     {

Modified: code/player/trunk/server/drivers/wsn/rcore_xbridge.cc
===================================================================
--- code/player/trunk/server/drivers/wsn/rcore_xbridge.cc       2008-12-18 
19:43:37 UTC (rev 7205)
+++ code/player/trunk/server/drivers/wsn/rcore_xbridge.cc       2008-12-18 
19:58:30 UTC (rev 7206)
@@ -309,9 +309,6 @@
                            player_msghdr * hdr,
                            void * data)
 {
-    assert (hdr);
-    assert (data);
-
     if (Message::MatchMessage (hdr, PLAYER_MSGTYPE_REQ,
         PLAYER_WSN_REQ_POWER, device_addr))
     {


This was sent by the SourceForge.net collaborative development platform, the 
world's largest Open Source development site.

------------------------------------------------------------------------------
SF.Net email is Sponsored by MIX09, March 18-20, 2009 in Las Vegas, Nevada.
The future of the web can't happen without you.  Join us at MIX09 to help
pave the way to the Next Web now. Learn more and register at
http://ad.doubleclick.net/clk;208669438;13503038;i?http://2009.visitmix.com/
_______________________________________________
Playerstage-commit mailing list
Playerstage-commit@lists.sourceforge.net
https://lists.sourceforge.net/lists/listinfo/playerstage-commit

Reply via email to