Home
FAQ
Player
Stage
Gazebo
Contrib
Documentation
Publications
Contributors
Users

Project
Download
Bugs/Feedback
Mailing lists

Radish

Old news
Old stuff

playerclient.h

Go to the documentation of this file.
00001 /*
00002  *  Player - One Hell of a Robot Server
00003  *  Copyright (C) 2000-2003
00004  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00005  *                      
00006  *
00007  *  This program is free software; you can redistribute it and/or modify
00008  *  it under the terms of the GNU General Public License as published by
00009  *  the Free Software Foundation; either version 2 of the License, or
00010  *  (at your option) any later version.
00011  *
00012  *  This program is distributed in the hope that it will be useful,
00013  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00014  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00015  *  GNU General Public License for more details.
00016  *
00017  *  You should have received a copy of the GNU General Public License
00018  *  along with this program; if not, write to the Free Software
00019  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00020  *
00021  */
00022 /*
00023  *  Player - One Hell of a Robot Server
00024  *  Copyright (C) 2003
00025  *     Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
00026  *                      
00027  *
00028  *  This library is free software; you can redistribute it and/or
00029  *  modify it under the terms of the GNU Lesser General Public
00030  *  License as published by the Free Software Foundation; either
00031  *  version 2.1 of the License, or (at your option) any later version.
00032  *
00033  *  This library is distributed in the hope that it will be useful,
00034  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00035  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00036  *  Lesser General Public License for more details.
00037  *
00038  *  You should have received a copy of the GNU Lesser General Public
00039  *  License along with this library; if not, write to the Free Software
00040  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00041  */
00042 
00043 /*
00044  * $Id: playerclient.h,v 1.150 2005/05/03 00:23:59 gerkey Exp $
00045  *
00046  * the C++ client
00047  */
00048 
00085 #ifndef PLAYERCLIENT_H
00086 #define PLAYERCLIENT_H
00087 
00088 #include <player.h>       /* from the server; gives message types */
00089 #include <playercclient.h>  /* pure C networking building blocks */
00090 
00091 #if HAVE_STRINGS_H
00092   #include <strings.h>
00093 #endif
00094 
00095 #if PLAYERCLIENT_THREAD
00096   #include <pthread.h>
00097 #endif
00098 
00099 #include <sys/time.h>
00100 struct pollfd;
00101 #include <string.h>
00102 #include <math.h>
00103 
00104 #ifndef RTOD
00105 
00106 #define RTOD(r) ((r) * 180 / M_PI)
00107 #endif
00108 
00109 #ifndef DTOR
00110 
00111 #define DTOR(d) ((d) * M_PI / 180)
00112 #endif
00113 
00114 #ifndef NORMALIZE
00115 
00116 #define NORMALIZE(z) atan2(sin(z), cos(z))
00117 #endif
00118 
00119 // forward declaration for friending
00120 class PlayerClient;
00121 
00133 class ClientProxy
00134 {
00135   friend class PlayerClient; // ANSI C++ syntax?
00136 
00137   public:         
00140     PlayerClient* client;
00141 
00144     bool valid;
00145 
00150     bool fresh;
00151 
00154     // functionality currently disabled, until it is fixed to handle
00155     // big messages.
00156 #if 0
00157     unsigned char last_data[PLAYER_MAX_MESSAGE_SIZE];
00158     player_msghdr_t last_header;
00159 #endif
00160 
00161     unsigned char access;   // 'r', 'w', or 'a' (others?)
00162     player_device_id_t m_device_id;
00163 
00166     char driver_name[PLAYER_MAX_DEVICE_STRING_LEN]; // driver in use
00167 
00170     struct timeval timestamp;  
00171 
00174     struct timeval senttime;   
00175 
00178     struct timeval receivedtime;
00179 
00191     ClientProxy(PlayerClient* pc, 
00192                 unsigned short req_device,
00193                 unsigned short req_index,
00194                 unsigned char req_access = 'c');
00195 
00196     // destructor will try to close access to the device
00197     virtual ~ClientProxy();
00198 
00201     unsigned char GetAccess() { return(access); };  
00202 
00206     int ChangeAccess(unsigned char req_access, 
00207                      unsigned char* grant_access=NULL );
00208 
00211     int Close() { return(ChangeAccess('c')); }
00212 
00215     virtual void FillData(player_msghdr_t hdr, const char* buffer);
00216 
00219     // functionality currently disabled, until it is fixed to handle
00220     // big messages.
00221 #if 0
00222     void StoreData(player_msghdr_t hdr, const char* buffer);
00223 #endif
00224     
00227     virtual void Print();
00228 
00229 
00237         int Lock();
00238         int Unlock();
00239   protected:
00240 #ifdef PLAYERCLIENT_THREAD
00241     pthread_mutex_t update_lock;
00242 #endif
00243 };
00244 
00245 
00247 class ClientProxyNode
00248 {
00249   public:
00250     ClientProxy* proxy;
00251     ClientProxyNode* next;
00252 };
00253 
00254 
00262 class PlayerClient
00263 {
00264   private:
00265     // special flag to indicate that we are being destroyed
00266     bool destroyed;
00267 
00268     // list of proxies associated with us
00269     ClientProxyNode* proxies;
00270     int num_proxies;
00271 
00272     int reserved;
00273 
00274     unsigned char data_delivery_mode;
00275     
00276     // get the pointer to the proxy for the given device and index
00277     //
00278     // returns NULL if we can't find it.
00279     //
00280     ClientProxy* GetProxy(unsigned short device, 
00281                                         unsigned short index);
00282     ClientProxy* GetProxy(player_device_id_t id);
00283 
00284   public:
00285     //  Struct containing information about the  connection to Player
00286     player_connection_t conn;
00287 
00288     // are we connected? 
00289     bool connected;
00290 
00291     //void SetReserved(int res) { reserved = res; }
00292     //int GetReserved() { return(reserved); }
00293 
00298     bool fresh; 
00299 
00302     char hostname[256]; 
00303 
00306     int port;
00307     
00308     // store the IP of the host, too - more efficient for
00309     // matching, etc, then the string
00310     struct in_addr hostaddr;
00311 
00314     struct timeval timestamp;
00315 
00319     int id_count;
00320     player_device_id_t ids[PLAYER_MAX_DEVICES];
00321     char drivernames[PLAYER_MAX_DEVICES][PLAYER_MAX_DEVICE_STRING_LEN];
00322 
00323     // constructors
00324     
00329     PlayerClient(const char* hostname=NULL,
00330                  const int port=PLAYER_PORTNUM,
00331                  const int protocol=PLAYER_TRANSPORT_TCP);
00332 
00336     PlayerClient(const struct in_addr* hostaddr,
00337                  const int port,
00338                  const int protocol=PLAYER_TRANSPORT_TCP);
00339 
00340     // destructor
00341     ~PlayerClient();
00342 
00346     int Connect(const char* hostname="localhost", int port=PLAYER_PORTNUM);
00347 
00351     int Connect(const struct in_addr* addr, int port);
00352 
00357     int ConnectRNS(const char* robotname, const char* hostname="localhost",
00358                    int port=PLAYER_PORTNUM);
00359 
00363     int Disconnect();
00364 
00367     bool Connected() { return((conn.sock >= 0) ? true : false); }
00368 
00378     int Peek(int timeout=0);
00379 
00397     int Read(bool await_sync=true, ClientProxy** dev=NULL);
00398     
00402     int Write(player_device_id_t device_id,
00403               const char* command, size_t commandlen);
00404 
00408     int Request(player_device_id_t device_id,
00409                 const char* payload,
00410                 size_t payloadlen,
00411                 player_msghdr_t* replyhdr,
00412                 char* reply, size_t replylen);
00413 
00419     int Request(player_device_id_t device_id,
00420                 const char* payload,
00421                 size_t payloadlen);
00422     
00430     int RequestDeviceAccess(player_device_id_t device_id,
00431                             unsigned char req_access,
00432                             unsigned char* grant_access,
00433                             char* driver_name = NULL,
00434                             int driver_name_len = 0);
00435 
00436     // Player device configurations
00437 
00444     int SetFrequency(unsigned short freq);
00445 
00455     int SetDataMode(unsigned char mode);
00456 
00460     int RequestData();
00461 
00465     int Authenticate(char* key);
00466 
00469     int LookupPort(const char* name);
00470     
00471     // proxy list management methods
00472 
00473     // add a proxy to the list
00474     void AddProxy(ClientProxy* proxy);
00475     // remove a proxy from the list
00476     void RemoveProxy(ClientProxy* proxy);
00477 
00478     // Get the list of available device ids. The data is written into the
00479     // proxy structure rather than retured to the caller.
00480     int GetDeviceList(); 
00481 };
00482 
00483 // forward declaration to avoid including <sys/poll.h>, which may not be
00484 // available when people are building clients against this lib
00485 struct pollfd;
00486 
00494 class PlayerMultiClient
00495 {
00496   private:
00497     // dynamically managed array of our clients
00498     PlayerClient** clients;
00499     //int num_clients;
00500     int size_clients;
00501 
00502     // dynamically managed array of structs that we'll give to poll(2)
00503     struct pollfd* ufds;
00504     int size_ufds;
00505     int num_ufds;
00506 
00507   public:
00510     PlayerMultiClient();
00511     
00512     // destructor
00513     ~PlayerMultiClient();
00514 
00517     int GetNumClients(void) { return num_ufds; };
00518 
00521     PlayerClient* GetClient( char* host, int port );
00522 
00525     PlayerClient* GetClient( struct in_addr* addr, int port );
00526     
00530     void AddClient(PlayerClient* client);
00531     
00534     void RemoveClient(PlayerClient* client);
00535 
00542     int Read();
00543 
00546     int ReadLatest( int max_reads );
00547 };
00548 
00558 class AIOProxy : public ClientProxy
00559 {
00560 
00561 public:
00565     AIOProxy (PlayerClient* pc, unsigned short index,
00566                    unsigned char access = 'c')
00567             : ClientProxy(pc,PLAYER_AIO_CODE,index,access)
00568       {}
00569 
00570     ~AIOProxy()
00571       {}
00572 
00574     char count;
00575 
00577     int anin[PLAYER_AIO_MAX_SAMPLES];
00578 
00579     // interface that all proxies must provide
00580     void FillData (player_msghdr_t hdr, const char* buffer);
00581 
00583     void Print ();
00584 };
00585 
00586 
00591 class GpsProxy : public ClientProxy
00592 {
00593   public:
00594     
00596     double latitude;
00597     double longitude;
00598 
00600     double altitude;
00601 
00603     int satellites;
00604 
00606     int quality;
00607     
00609     double hdop;
00610 
00612     double vdop;
00613 
00615     double utm_easting;
00616     double utm_northing;
00617 
00619     struct timeval time;
00620    
00623     GpsProxy(PlayerClient* pc, unsigned short index, 
00624               unsigned char access='c') :
00625             ClientProxy(pc,PLAYER_GPS_CODE,index,access) {}
00626 
00627     // interface that all proxies must provide
00628     void FillData(player_msghdr_t hdr, const char* buffer);
00629     
00631     void Print();
00632 };
00633 
00634 
00635 
00636 
00637 /* Gripper stuff */
00638 #define GRIPopen   1
00639 #define GRIPclose  2
00640 #define GRIPstop   3
00641 #define LIFTup     4
00642 #define LIFTdown   5
00643 #define LIFTstop   6
00644 #define GRIPstore  7
00645 #define GRIPdeploy 8
00646 #define GRIPhalt   15
00647 #define GRIPpress  16
00648 #define LIFTcarry  17
00649 
00656 class GripperProxy : public ClientProxy
00657 {
00658 
00659   public:
00660     
00662     unsigned char state,beams;
00663 
00666     bool outer_break_beam,inner_break_beam,
00667          paddles_open,paddles_closed,paddles_moving,
00668          gripper_error,lift_up,lift_down,lift_moving,
00669          lift_error;
00670 
00673     GripperProxy(PlayerClient* pc, unsigned short index, 
00674                  unsigned char access='c') :
00675             ClientProxy(pc,PLAYER_GRIPPER_CODE,index,access) {}
00676 
00677     // these methods are the user's interface to this device
00678 
00683     int SetGrip(unsigned char cmd, unsigned char arg=0);
00684 
00685     // interface that all proxies must provide
00686     void FillData(player_msghdr_t hdr, const char* buffer);
00687     
00689     void Print();
00690 };
00691 
00692 
00698 class SoundProxy : public ClientProxy
00699 {
00700 
00701   public:
00702     
00705     SoundProxy(PlayerClient* pc, unsigned short index, 
00706                  unsigned char access='c') :
00707             ClientProxy(pc,PLAYER_SOUND_CODE,index,access) {}
00708 
00709     // these methods are the user's interface to this device
00710     
00714     int Play(int index);
00715 
00716     // interface that all proxies must provide
00717     void FillData(player_msghdr_t hdr, const char* buffer) {};
00718     
00720     void Print() {};
00721 };
00722 
00723 
00724 class FiducialItem
00725 {
00726   public:
00727     int id;
00728     double pose[3];
00729     double upose[3];
00730 };
00731 
00732 
00739 class FiducialProxy : public ClientProxy
00740 {
00741 
00742   public:
00743   // the latest laser beacon data
00744 
00747   unsigned short count;
00748 
00751   double pose[3];
00752 
00755   double size[2];
00756 
00759   double fiducial_size[2];
00760 
00763   double min_range;
00764   
00767   double max_range;
00768 
00771   double view_angle;
00772 
00774   FiducialItem beacons[PLAYER_FIDUCIAL_MAX_SAMPLES];
00775      
00778   FiducialProxy(PlayerClient* pc, unsigned short index,
00779                 unsigned char access='c') :
00780     ClientProxy(pc,PLAYER_FIDUCIAL_CODE,index,access) { count=0; }
00781     
00782   // interface that all proxies must provide
00783   void FillData(player_msghdr_t hdr, const char* buffer);
00784     
00786   void Print();
00787 
00789   int PrintFOV();
00790 
00792   int PrintGeometry();
00793 
00795   int GetConfigure();
00796  
00798   int GetFOV();
00799 
00805   int SetId( int id );
00806 
00811   int GetId( void );
00812 
00818   int SetFOV( double min_range, 
00819               double max_range, 
00820               double view_angle);
00821   
00831   int SendMessage( player_fiducial_msg_t* msg, bool consume );
00832   
00842   int RecvMessage( player_fiducial_msg_t* msg, bool consume );
00843 
00844 };
00845 
00846 
00847 
00854 class LaserProxy : public ClientProxy
00855 {
00856 
00857   public:
00858 
00860     int scan_count;
00861 
00864     double scan_res;
00865 
00868     double min_angle, max_angle;
00869     
00871     double range_res;
00872 
00874     bool intensity;
00875 
00877     double scan[PLAYER_LASER_MAX_SAMPLES][2];
00878 
00880     double point[PLAYER_LASER_MAX_SAMPLES][2];
00881 
00882     // TODO: haven't verified that intensities work yet:
00884     unsigned char intensities[PLAYER_LASER_MAX_SAMPLES];
00885 
00886     double min_right,min_left;
00887    
00890     LaserProxy(PlayerClient* pc, unsigned short index, 
00891                unsigned char access='c') :
00892         ClientProxy(pc,PLAYER_LASER_CODE,index,access) {}
00893 
00894     // these methods are the user's interface to this device
00895 
00905     int SetLaserState(const unsigned char state);
00906 
00916     int Configure(double min_angle, 
00917                   double max_angle, 
00918                   unsigned int scan_res,
00919                   unsigned int range_res, 
00920                   bool intensity);
00921 
00925     int GetConfigure();
00926 
00928     int RangeCount() { return scan_count; }
00929 
00931     double Ranges (int index)
00932     {
00933       if (index < scan_count)
00934         return scan[index][0];
00935       else
00936         return 0;
00937     }
00938     double MinLeft () { return min_left; }
00939     double MinRight () { return min_right; }
00940 
00946     double operator [] (unsigned int index)
00947     {
00948       return Ranges(index);
00949     }
00950     
00951     // interface that all proxies must provide
00952     void FillData(player_msghdr_t hdr, const char* buffer);
00953     
00955     void Print();
00956 
00958     void PrintConfig();
00959 };
00960 
00961 
00962  
00963 class localize_hypoth
00964 {
00965   public:
00966     // Pose estimate (m, m, radians)
00967     double mean[3];
00968     // Covariance (m^2, radians^2)
00969     double cov[3][3];
00970     // Weight associated with this hypothesis
00971     double weight;
00972 };
00973 
00980 class LocalizeProxy : public ClientProxy
00981 {
00982 
00983   public:
00985     unsigned int map_size_x, map_size_y;
00986 
00988     double map_scale;
00989 
00991     int8_t *map_cells;
00992 
00994     int pending_count;
00995     
00997     int hypoth_count;
00998 
01000     localize_hypoth hypoths[PLAYER_LOCALIZE_MAX_HYPOTHS];
01001 
01002 
01006     LocalizeProxy(PlayerClient* pc, unsigned short index, 
01007                   unsigned char access = 'c') :
01008             ClientProxy(pc,PLAYER_LOCALIZE_CODE,index,access)
01009     { map_cells=NULL; bzero(&hypoths,sizeof(hypoths)); }
01010 
01011     ~LocalizeProxy();
01012 
01013     // these methods are the user's interface to this device
01014     
01015     // interface that all proxies must provide
01016     void FillData(player_msghdr_t hdr, const char* buffer);
01017 
01021     int SetPose(double pose[3], double cov[3][3]);
01022 
01026     int GetNumParticles();
01027 
01028     // deprecated: get map from map interface instead
01029 #if 0
01030     int GetMap();
01031 #endif
01032     
01034     void Print();
01035 };
01036 
01037 
01043 class MotorProxy : public ClientProxy
01044 {
01045   private:
01047   double theta;
01048 
01050   double thetaspeed;;
01051 
01053   unsigned char stall;
01054 
01055   public:
01058   MotorProxy(PlayerClient* pc, unsigned short index,
01059              unsigned char access ='c') :
01060     ClientProxy(pc,PLAYER_MOTOR_CODE,index,access) {}
01061 
01062   // these methods are the user's interface to this device
01063 
01068   int SetSpeed(double speed);
01069 
01074   int GoTo(double angle);
01075 
01076 
01083   int SetMotorState(unsigned char state);
01084 
01091   int SelectVelocityControl(unsigned char mode);
01092 
01096   int ResetOdometry();
01097 
01102   int SetOdometry(double angle);
01103 
01109   int SelectPositionMode(unsigned char mode);
01110 
01115   int SetSpeedPID(double kp, double ki, double kd);
01116 
01121   int SetPositionPID(double kp, double ki, double kd);
01122 
01128   int SetPositionSpeedProfile(double spd, double acc);
01129 
01131   double  Theta () const { return theta; }
01132 
01134   double  ThetaSpeed () const { return thetaspeed; }
01135 
01137   unsigned char Stall () const { return stall; }
01138 
01139   // interface that all proxies must provide
01140   void FillData(player_msghdr_t hdr, const char* buffer);
01141 
01143   void Print();
01144 };
01145 
01151 class PositionProxy : public ClientProxy
01152 {
01153 
01154   public:
01158   double pose[3];
01159   double size[2];
01160 
01162   double xpos,ypos,theta;
01163 
01165   double speed, sidespeed, turnrate;
01166 
01168   unsigned char stall;
01169    
01172   PositionProxy(PlayerClient* pc, unsigned short index,
01173                 unsigned char access ='c') :
01174     ClientProxy(pc,PLAYER_POSITION_CODE,index,access) {}
01175 
01176   // these methods are the user's interface to this device
01177 
01181   int PositionProxy::GetGeometry();
01182 
01188   int SetSpeed(double speed, double sidespeed, double turnrate);
01189 
01192   int SetSpeed(double speed, double turnrate)
01193       { return(SetSpeed(speed,0.0,turnrate));}
01194 
01199   int GoTo(double x, double y, double t);
01200 
01201 
01208   int SetMotorState(unsigned char state);
01209     
01221   int SelectVelocityControl(unsigned char mode);
01222    
01226   int ResetOdometry();
01227 
01228   // the following ioctls are currently only supported by reb_position
01229   //
01230 
01235   int SelectPositionMode(unsigned char mode);
01236 
01241   int SetOdometry(double x, double y, double t);
01242 
01244   int SetSpeedPID(int kp, int ki, int kd);
01245 
01247   int SetPositionPID(short kp, short ki, short kd);
01248 
01250   int SetPositionSpeedProfile(short spd, short acc);
01251 
01253   int DoStraightLine(int mm);
01254 
01256   int DoRotation(int deg);
01257 
01259   int DoDesiredHeading(int theta, int xspeed, int yawspeed);
01260 
01262   int SetStatus(uint8_t cmd, uint16_t value);
01263 
01265   int PlatformShutdown();
01266 
01268   double  Xpos () const { return xpos; }
01269   
01271   double  Ypos () const { return ypos; }
01272   
01274   double Theta () const { return theta; }
01275   
01277   double  Speed () const { return speed; }
01278 
01280   double  SideSpeed () const { return sidespeed; }
01281 
01283   double  TurnRate () const { return turnrate; }
01284   
01286   unsigned char Stall () const { return stall; }
01287 
01288   // interface that all proxies must provide
01289   void FillData(player_msghdr_t hdr, const char* buffer);
01290     
01292   void Print();
01293 };
01294 
01295 
01301 class Position2DProxy : public ClientProxy
01302 {
01303   private:
01305   double xpos,ypos,yaw;
01306 
01308   double xspeed, yspeed, yawspeed;
01309 
01311   unsigned char stall;
01312 
01313   public:
01316   Position2DProxy(PlayerClient* pc, unsigned short index,
01317                 unsigned char access ='c') :
01318     ClientProxy(pc,PLAYER_POSITION_CODE,index,access) {}
01319 
01320   // these methods are the user's interface to this device
01321 
01327   int SetSpeed(double xspeed, double yspeed, double yawspeed);
01328 
01331   int SetSpeed(double speed, double turnrate)
01332       { return(SetSpeed(speed,0.0,turnrate));}
01333 
01338   int GoTo(double x, double y, double yaw);
01339 
01340 
01347   int SetMotorState(unsigned char state);
01348 
01360   int SelectVelocityControl(unsigned char mode);
01361 
01365   int ResetOdometry();
01366 
01367   // the following ioctls are currently only supported by reb_position
01368   //
01369 
01374   int SelectPositionMode(unsigned char mode);
01375 
01380   int SetOdometry(double x, double y, double yaw);
01381 
01383   int SetSpeedPID(double kp, double ki, double kd);
01384 
01386   int SetPositionPID(double kp, double ki, double kd);
01387 
01390   int SetPositionSpeedProfile(double spd, double acc);
01391 
01393   int DoStraightLine(double m);
01394 
01396   int DoRotation(double yawspeed);
01397 
01399   int DoDesiredHeading(double yaw, double xspeed, double yawspeed);
01400 
01402   int SetStatus(uint8_t cmd, uint16_t value);
01403 
01405   int PlatformShutdown();
01406 
01408   double  Xpos () const { return xpos; }
01409 
01411   double  Ypos () const { return ypos; }
01412 
01414   double Yaw () const { return yaw; }
01415 
01416   // Speed, SideSpeed, and TurnRate are left for backwards compatibility, but
01417   // could probably be dropped.
01418 
01420   double  Speed () const { return xspeed; }
01422   double  SideSpeed () const { return yspeed; }
01424   double  TurnRate () const { return yawspeed; }
01425 
01426 
01428   double  XSpeed () const { return xspeed; }
01429 
01431   double  YSpeed () const { return yspeed; }
01432 
01434   double  YawSpeed () const { return yawspeed; }
01435 
01436 
01438   unsigned char Stall () const { return stall; }
01439 
01440   // interface that all proxies must provide
01441   void FillData(player_msghdr_t hdr, const char* buffer);
01442 
01444   void Print();
01445 };
01446 
01453 class Position3DProxy : public ClientProxy
01454 {
01455   private:
01456 
01458   double xpos,ypos,zpos;
01459   double roll,pitch,yaw;
01460 
01462   double xspeed, yspeed, zspeed;
01463   double rollspeed, pitchspeed, yawspeed;
01464 
01466   unsigned char stall;
01467 
01468   public:
01469 
01472   Position3DProxy(PlayerClient* pc, unsigned short index,
01473                   unsigned char access ='c') :
01474     ClientProxy(pc,PLAYER_POSITION3D_CODE,index,access) {}
01475 
01476   // these methods are the user's interface to this device
01477 
01484   int SetSpeed(double xspeed, double yspeed, double zspeed,
01485                double rollspeed, double pitchspeed, double yawspeed);
01486 
01492   int Position3DProxy::SetSpeed(double xspeed,double yspeed,
01493                                 double zspeed,double yawspeed)
01494   { return(SetSpeed(xspeed,yspeed,zspeed,0,0,yawspeed)); }
01495 
01496   int SetSpeed(double xspeed, double yspeed, double yawspeed)
01497     {  return SetSpeed(xspeed, yspeed, 0, 0, 0, yawspeed); }
01498 
01501   int SetSpeed(double xspeed, double yawspeed)
01502       { return(SetSpeed(xspeed,0,0,0,0,yawspeed));}
01503 
01504 
01509   int GoTo(double x, double y, double z,
01510            double roll, double pitch, double yaw);
01511 
01518   int SetMotorState(unsigned char state);
01519 
01525   int SelectVelocityControl(unsigned char mode);
01526 
01530   int ResetOdometry();
01531 
01538   int SetOdometry(double x, double y, double z,
01539                   double roll, double pitch, double yaw);
01540 
01545   int SelectPositionMode(unsigned char mode);
01546 
01548   int SetSpeedPID(double kp, double ki, double kd);
01549 
01551   int SetPositionPID(double kp, double ki, double kd);
01552 
01555   int SetPositionSpeedProfile(double spd, double acc);
01556 
01557   // interface that all proxies must provide
01558   void FillData(player_msghdr_t hdr, const char* buffer);
01559 
01561   void Print();
01562 
01564   double  Xpos() const { return xpos; }
01565 
01567   double  Ypos() const { return ypos; }
01568 
01570   double  Zpos() const { return zpos; }
01571 
01573   double  Roll() const { return roll; }
01574 
01576   double  Pitch() const { return pitch; }
01577 
01579   double  Yaw() const { return yaw; }
01580 
01582   double  XSpeed() const { return xspeed; }
01583 
01585   double  YSpeed() const { return yspeed; }
01586 
01588   double  ZSpeed() const { return zspeed; }
01589 
01591   double  RollSpeed() const { return rollspeed; }
01592 
01594   double  PitchSpeed() const { return pitchspeed; }
01595 
01597   double  YawSpeed() const { return yawspeed; }
01598 
01600   unsigned char Stall () const { return stall; }
01601 };
01602 
01609 class PtzProxy : public ClientProxy
01610 {
01611   public:
01612     
01614     double pan, tilt, zoom;
01616     double panspeed, tiltspeed;
01617 
01621     PtzProxy(PlayerClient* pc, unsigned short index, 
01622              unsigned char access='c') :
01623             ClientProxy(pc,PLAYER_PTZ_CODE,index,access) {}
01624 
01625     // these methods are the user's interface to this device
01626 
01632     int SetCam(double pan, double tilt, double zoom);
01633 
01635     int SetSpeed(double panspeed, double tiltspeed);
01636 
01637     // interface that all proxies must provide
01638     void FillData(player_msghdr_t hdr, const char* buffer);
01639     
01641     int SendConfig(uint8_t *bytes, size_t len, uint8_t *reply = NULL, 
01642                    size_t reply_len = 0);
01643     
01646     int SelectControlMode(uint8_t mode);
01647 
01649     void Print();
01650 };
01651 
01652 
01659 class SonarProxy : public ClientProxy
01660 {
01661 
01662   public:
01665     unsigned short range_count;
01666 
01670     double ranges[PLAYER_SONAR_MAX_SAMPLES];
01671 
01674     int pose_count;
01675 
01678     double poses[PLAYER_SONAR_MAX_SAMPLES][3];
01679    
01683     SonarProxy(PlayerClient* pc, unsigned short index, 
01684                unsigned char access = 'c') :
01685             ClientProxy(pc,PLAYER_SONAR_CODE,index,access)
01686     { 
01687       memset(&poses,0,sizeof(poses)); 
01688       range_count=pose_count=0;
01689     }
01690 
01691     // these methods are the user's interface to this device
01692     
01701     int SetSonarState(unsigned char state);
01702 
01704     int GetSonarGeom();
01705 
01711     double operator [](unsigned int index) 
01712     { 
01713       if(index < sizeof(ranges))
01714         return(ranges[index]);
01715       else 
01716         return(0);
01717     }
01718 
01719     // interface that all proxies must provide
01720     void FillData(player_msghdr_t hdr, const char* buffer);
01721     
01723     void Print();
01724 };
01725 
01731 class SpeechProxy : public ClientProxy
01732 {
01733 
01734   public:
01735    
01739     SpeechProxy(PlayerClient* pc, unsigned short index, 
01740                 unsigned char access='c') :
01741             ClientProxy(pc,PLAYER_SPEECH_CODE,index,access) {}
01742 
01743     // these methods are the user's interface to this device
01744 
01749     int Say(char* str);
01750 };
01751 
01762 class TruthProxy : public ClientProxy
01763 {
01764   
01765   public:
01766 
01772   double px, py, pz, rx, ry, rz; 
01773 
01776   TruthProxy(PlayerClient* pc, unsigned short index, 
01777              unsigned char access = 'c') :
01778     ClientProxy(pc,PLAYER_TRUTH_CODE,index,access) {};
01779 
01780     
01781   // interface that all proxies must provide
01782   void FillData(player_msghdr_t hdr, const char* buffer);
01783     
01785   void Print();
01786 
01793   int GetPose( double *px, double *py, double *pz,
01794                double *rx, double *ry, double *rz );
01795 
01799   int SetPose( double px, double py, double pz,
01800                double rx, double ry, double rz);
01801 
01804   int SetPoseOnRoot(  double px, double py, double pz,
01805                       double rx, double ry, double rz);
01806 
01810   int GetFiducialID( int16_t* id );
01811 
01815   int SetFiducialID( int16_t id );
01816 
01817 };
01818 
01819 class Blob
01820 {
01821   public:
01822     unsigned int id;
01823     unsigned int color;
01824     unsigned int area;
01825     unsigned short x;
01826     unsigned short y;
01827     unsigned short left;
01828     unsigned short right;
01829     unsigned short top;
01830     unsigned short bottom;
01831     double range;
01832 };
01833 
01841 class BlobfinderProxy : public ClientProxy
01842 {
01843 
01844   public:
01845     
01847     unsigned short width, height;
01848 
01850     int blob_count;
01852     Blob blobs[PLAYER_BLOBFINDER_MAX_BLOBS];
01853    
01857     BlobfinderProxy(PlayerClient* pc, unsigned short index, 
01858                 unsigned char access='c');
01859     ~BlobfinderProxy();
01860 
01861     // these methods are the user's interface to this device
01862 
01863     // interface that all proxies must provide
01864     void FillData(player_msghdr_t hdr, const char* buffer);
01865     
01867     void Print();
01868 
01869     int SetTrackingColor();
01870     int SetTrackingColor(int rmin, int rmax, int gmin,
01871                          int gmax, int bmin, int bmax);
01872     int SetImagerParams(int contrast, int brightness,
01873                          int autogain, int colormode);
01874     int SetContrast(int c);
01875     int SetColorMode(int m);
01876     int SetBrightness(int b);
01877     int SetAutoGain(int g);
01878 
01879 };
01880 
01881 
01882 // these define default coefficients for our 
01883 // range and standard deviation estimates
01884 #define IRPROXY_DEFAULT_DIST_M_VALUE -0.661685227
01885 #define IRPROXY_DEFAULT_DIST_B_VALUE  10.477102515
01886 
01887 #define IRPROXY_DEFAULT_STD_M_VALUE  1.913005560938
01888 #define IRPROXY_DEFAULT_STD_B_VALUE -7.728130591833
01889 
01890 #define IRPROXY_M_PARAM 0
01891 #define IRPROXY_B_PARAM 1
01892 
01893 //this is the effective range of the sensor in mm
01894 #define IRPROXY_MAX_RANGE 700
01895 
01901 class IRProxy : public ClientProxy
01902 {
01903 public:
01904 
01906   unsigned short ranges[PLAYER_IR_MAX_SAMPLES];
01907   
01909   unsigned short voltages[PLAYER_IR_MAX_SAMPLES];
01910 
01912   double stddev[PLAYER_IR_MAX_SAMPLES];
01913 
01915   double params[PLAYER_IR_MAX_SAMPLES][2]; 
01916 
01918   double sparams[PLAYER_IR_MAX_SAMPLES][2]; 
01919 
01921   player_ir_pose_t ir_pose;
01922 
01924   IRProxy(PlayerClient *pc, unsigned short index,
01925           unsigned char access = 'c');
01926 
01928   int SetIRState(unsigned char state);
01929 
01931   int GetIRPose();
01932 
01934   void SetRangeParams(int which, double m, double );
01935 
01937   void SetStdDevParams(int which, double m, double b);
01938 
01940   double CalcStdDev(int w, unsigned short range);
01941 
01947   unsigned short operator [](unsigned int index) 
01948   {
01949     if (index < PLAYER_IR_MAX_SAMPLES) {
01950       return ranges[index];
01951     } 
01952 
01953     return 0;
01954   }
01955 
01956   // required methods
01957   void FillData(player_msghdr_t hdr, const char *buffer);
01958 
01960   void Print();
01961 };
01962 
01966 class WiFiProxy: public ClientProxy
01967 {
01968 public:
01969 
01970 
01974   WiFiProxy(PlayerClient *pc, unsigned short index, 
01975                unsigned char access = 'c') :
01976     ClientProxy(pc, PLAYER_WIFI_CODE, index, access), link_count(0) {}
01977 
01978 
01979   int GetLinkQuality(char * ip = NULL);
01980   int GetLevel(char * ip = NULL);
01981   int GetLeveldBm(char * ip = NULL) { return GetLevel(ip) - 0x100; }
01982   int GetNoise(char * ip = NULL);
01983   int GetNoisedBm(char * ip = NULL) { return GetNoise(ip) - 0x100; }
01984 
01985   uint16_t GetMaxLinkQuality() { return maxqual; }
01986   uint8_t GetMode() { return op_mode; }
01987 
01988   int GetBitrate();
01989 
01990   char * GetMAC(char *buf, int len);
01991 
01992   char * GetIP(char *buf, int len);
01993   char * GetAP(char *buf, int len);
01994 
01995   int AddSpyHost(char *address);
01996   int RemoveSpyHost(char *address);
01997 
01998   void FillData(player_msghdr_t hdr, const char *buffer);
01999 
02001   void Print();
02002 
02003 protected:
02004   int GetLinkIndex(char *ip);
02005 
02007   int link_count;
02008   player_wifi_link_t links[PLAYER_WIFI_MAX_LINKS];
02009   uint32_t throughput;
02010   uint8_t op_mode;
02011   int32_t bitrate;
02012   uint16_t qual_type, maxqual, maxlevel, maxnoise;
02013   
02014   char access_point[32];
02015 
02016 };
02017 
02021 class PowerProxy : public ClientProxy 
02022 {
02023 
02024   public:
02028     PowerProxy (PlayerClient* pc, unsigned short index,
02029                 unsigned char access ='c')
02030             : ClientProxy(pc,PLAYER_POWER_CODE,index,access) {}
02031 
02033     double Charge () const { return charge; }
02034 
02035     // interface that all proxies must provide
02036     void FillData (player_msghdr_t hdr, const char* buffer);
02037 
02039     void Print ();
02040 
02041   private:
02042     // Remaining power in volts
02043     double charge;
02044 };
02045 
02046 
02051 class AudioProxy : public ClientProxy 
02052 {
02053 
02054   public:
02056     uint16_t frequency0, amplitude0;
02058     uint16_t frequency1, amplitude1;
02060     uint16_t frequency2, amplitude2;
02062     uint16_t frequency3, amplitude3;
02064     uint16_t frequency4, amplitude4;
02065 
02069     AudioProxy (PlayerClient* pc, unsigned short index,
02070                 unsigned char access ='c')
02071             : ClientProxy(pc,PLAYER_AUDIO_CODE,index,access) {}
02072 
02073     // interface that all proxies must provide
02074     void FillData (player_msghdr_t hdr, const char* buffer);
02075 
02077     int PlayTone(unsigned short freq, unsigned short amp, unsigned short dur);
02078 
02080     void Print ();
02081 };
02082 
02087 class AudioDSPProxy : public ClientProxy 
02088 {
02089 
02090   public:
02092     int16_t sampleFormat;
02093 
02095     uint16_t sampleRate;
02096 
02098     uint8_t channels;
02099 
02100     uint16_t freq[5];
02101     uint16_t amp[5];
02102 
02106     AudioDSPProxy (PlayerClient* pc, unsigned short index,
02107                 unsigned char access ='c')
02108             : ClientProxy(pc,PLAYER_AUDIODSP_CODE,index,access) {}
02109 
02110     int Configure(uint8_t channels, uint16_t sampleRate, 
02111         int16_t sampleFormat=0xFFFFFFFF );
02112 
02113     int GetConfigure();
02114 
02115     // interface that all proxies must provide
02116     void FillData (player_msghdr_t hdr, const char* buffer);
02117 
02119     int PlayTone(unsigned short freq, unsigned short amp, unsigned int dur);
02120     int PlayChirp(unsigned short freq, unsigned short amp, unsigned int dur,
02121         const unsigned char bitString[], unsigned short bitStringLen);
02122     int Replay();
02123 
02125     void Print ();
02126 };
02127 
02132 class AudioMixerProxy : public ClientProxy 
02133 {
02134 
02135   public:
02136     unsigned short masterLeft, masterRight;
02137     unsigned short pcmLeft, pcmRight;
02138     unsigned short lineLeft, lineRight;
02139     unsigned short micLeft, micRight;
02140     unsigned short iGain, oGain;
02141 
02145     AudioMixerProxy (PlayerClient* pc, unsigned short index,
02146                 unsigned char access ='c')
02147             : ClientProxy(pc,PLAYER_AUDIOMIXER_CODE,index,access) {}
02148 
02149     int GetConfigure();
02150 
02151     // interface that all proxies must provide
02152     void FillData (player_msghdr_t hdr, const char* buffer);
02153 
02154     int SetMaster(unsigned short left, unsigned short right);
02155     int SetPCM(unsigned short left, unsigned short right);
02156     int SetLine(unsigned short left, unsigned short right);
02157     int SetMic(unsigned short left, unsigned short right);
02158     int SetIGain(unsigned short gain);
02159     int SetOGain(unsigned short gain);
02160 
02161     // Print the current data.
02162     void Print ();
02163 };
02164 
02170 class BumperProxy : public ClientProxy 
02171 {
02172 
02173 public:
02177     BumperProxy (PlayerClient* pc, unsigned short index,
02178                    unsigned char access = 'c')
02179             : ClientProxy(pc,PLAYER_BUMPER_CODE,index,access) 
02180       {}
02181 
02182     ~BumperProxy()
02183       {}
02184 
02185     // these methods are the user's interface to this device
02186 
02189     bool Bumped (const unsigned int i);
02190 
02193     bool BumpedAny ();
02194 
02198     int GetBumperGeom( player_bumper_geom_t* bumper_defs );
02199 
02201     uint8_t BumperCount () const { return bumper_count; }
02202 
02203     // interface that all proxies must provide
02204     void FillData (player_msghdr_t hdr, const char* buffer);
02205 
02207     void Print ();
02208 
02209 private:
02212     uint8_t bumper_count;
02213     uint8_t bumpers[PLAYER_BUMPER_MAX_SAMPLES];
02214 };
02215 
02221 class DIOProxy : public ClientProxy 
02222 {
02223 
02224 public:
02228     DIOProxy (PlayerClient* pc, unsigned short index,
02229                    unsigned char access = 'c')
02230             : ClientProxy(pc,PLAYER_DIO_CODE,index,access) 
02231       {}
02232 
02233     ~DIOProxy()
02234       {}
02235 
02237     uint8_t count;
02238 
02240     uint32_t digin;
02241 
02243     int SetOutput(uint8_t output_count, uint32_t digout);
02244     
02245     // interface that all proxies must provide
02246     void FillData (player_msghdr_t hdr, const char* buffer);
02247 
02249     void Print ();
02250 };
02251  
02256 class WaveformProxy : public ClientProxy 
02257 {
02258 
02259 public:
02263   WaveformProxy (PlayerClient* pc, unsigned short index,
02264                  unsigned char access = 'c')
02265     : ClientProxy(pc,PLAYER_WAVEFORM_CODE,index,access) 
02266     {
02267       this->ConfigureDSP(); // use latest settings      
02268     }
02269   
02270   ~WaveformProxy();
02271   
02273     unsigned int bitrate;
02274 
02276     unsigned short depth;
02277 
02279     unsigned int last_samples;
02280 
02282     unsigned char buffer[PLAYER_WAVEFORM_DATA_MAX];
02283   
02285     int fd; 
02286   
02287     // interface that all proxies must provide
02288     void FillData (player_msghdr_t hdr, const char* buffer);
02289 
02291     void Print ();
02292 
02293     // set up the DSP to the current bitrate and depth
02294     int ConfigureDSP() ;
02295 
02296     // open the sound device 
02297     void OpenDSPforWrite();
02298 
02299     // Play the waveform through the DSP
02300     void Play();
02301 
02302 };
02303 
02312 class MComProxy : public ClientProxy 
02313 {
02314 
02315 public:
02318     player_mcom_data_t data;
02319     int type;
02320     char channel[MCOM_CHANNEL_LEN];
02321 
02322 public:
02323     MComProxy(PlayerClient* pc, unsigned short index, 
02324               unsigned char access = 'c') :
02325             ClientProxy(pc,PLAYER_MCOM_CODE,index,access){}
02326 
02333     int Pop(int type, char channel[MCOM_CHANNEL_LEN]);
02334 
02341     int Read(int type, char channel[MCOM_CHANNEL_LEN]);
02342 
02344     int Push(int type, char channel[MCOM_CHANNEL_LEN], char dat[MCOM_DATA_LEN]);
02345 
02347     int Clear(int type, char channel[MCOM_CHANNEL_LEN]);
02348 
02351   int SetCapacity(int type, char channel[MCOM_CHANNEL_LEN], unsigned char cap);
02352 
02355     char* LastData() { return data.data; }
02356 
02359     int LastMsgType() { return type; }
02360 
02363     char* LastChannel() { return channel; }
02364 
02365     void FillData(player_msghdr_t hdr, const char* buffer);
02366     void Print();
02367 };
02368 
02374 class BlinkenlightProxy : public ClientProxy 
02375 {
02376 
02377 public:
02381   BlinkenlightProxy (PlayerClient* pc, unsigned short index,
02382                      unsigned char access = 'c')
02383     : ClientProxy(pc,PLAYER_BLINKENLIGHT_CODE,index,access) 
02384     {
02385       // assume the light is off by default
02386       this->period_ms = 0;
02387       this->enable = false;
02388     }
02389   
02390   virtual ~BlinkenlightProxy()
02391     { };
02392   
02394   bool enable;
02395   
02400   int period_ms;
02401   
02402     // interface that all proxies must provide
02403     void FillData (player_msghdr_t hdr, const char* buffer);
02404 
02406     void Print ();
02407 
02412     int SetLight( bool enable, int period_ms );
02413 };
02414 
02419 class CameraProxy : public ClientProxy 
02420 {
02421 
02422 public:
02423     // Constructor.  Leave the access field empty to start unconnected.
02424    CameraProxy (PlayerClient *pc, unsigned short index,
02425        unsigned char access='c');
02426 
02427    virtual ~CameraProxy();
02428 
02429    // Image color depth
02430    uint8_t depth;
02431 
02432    // Image dimensions (pixels)
02433    uint16_t width, height;
02434 
02435    // Sime of the image (bytes)
02436    uint32_t imageSize;
02437 
02438    // Image data
02439    uint8_t* image;
02440 
02441    // interface that all proxies must provide
02442    void FillData(player_msghdr_t hdr, const char* buffer);
02443 
02444    // prints out basic statistics of the camera
02445    void Print();
02446 
02447    void SaveFrame(const char *prefix);
02448 
02449 private:
02450    char filename[256];
02451    int frameNo;
02452 };
02453 
02454 
02459 class PlannerProxy : public ClientProxy
02460 {
02461 
02462   // Constructor.  Leave the access field empty to start unconnected.
02463   public: PlannerProxy (PlayerClient *pc, unsigned short index,
02464               unsigned char access='c');
02465 
02466   // Destructor
02467   public: virtual ~PlannerProxy();
02468 
02470   public: int SetCmdPose( double gx, double gy, double ga);
02471 
02474   public: int GetWaypoints();
02475 
02478   public: int Enable(int state);
02479 
02480   // interface that all proxies must provide
02481   public: void FillData( player_msghdr_t hdr, const char *buffer);
02482 
02484   public: bool pathValid;
02485 
02487   public: bool pathDone;
02488 
02490   public: double px, py, pa;
02491 
02493   public: double gx, gy, ga;
02494 
02496   public: double wx, wy, wa;
02497 
02501   public: short currWaypoint;
02502 
02504   public: short waypointCount;
02505 
02507   public: double waypoints[PLAYER_PLANNER_MAX_WAYPOINTS][3];
02508 
02509 };
02510 
02516 class EnergyProxy : public ClientProxy 
02517 {
02518 
02519 public:
02523     EnergyProxy (PlayerClient* pc, unsigned short index,
02524                    unsigned char access = 'c')
02525             : ClientProxy(pc,PLAYER_ENERGY_CODE,index,access) 
02526       {}
02527 
02528     ~EnergyProxy()
02529       {}
02530 
02531     // these methods are the user's interface to this device
02532 
02533     // interface that all proxies must provide
02534     void FillData (player_msghdr_t hdr, const char* buffer);
02535 
02537     void Print ();
02538 
02545     double joules;
02546     double watts;
02547     bool charging;
02548 };
02549 
02554 class MapProxy : public ClientProxy
02555 {
02556   // Constructor
02557   public: MapProxy (PlayerClient *pc, unsigned short indes,
02558               unsigned char access='c');
02559 
02560   // Destructor
02561   public: ~MapProxy();
02562 
02564   public: int GetMap();
02565 
02567   public: int GetCellIndex( int x, int y );
02568 
02571   public: int GetCell( char* cell, int x, int y );
02572 
02573   // interface that all proxies must provide
02574   public: void FillData (player_msghdr_t hde, const char *buffer);
02575 
02577   public: double resolution;
02578 
02579   /* Map size, in cells */
02580   public: int width, height;
02581 
02583   public: char *cells;
02584 };
02585 
02586 
02590 class SpeechRecognitionProxy : public ClientProxy
02591 {
02592   // Constructor
02593   public: SpeechRecognitionProxy (PlayerClient *pc, unsigned short indes,
02594               unsigned char access='c');
02595 
02596   // Destructor
02597   public: ~SpeechRecognitionProxy();
02598 
02599   // interface that all proxies must provide
02600   public: void FillData (player_msghdr_t hde, const char *buffer);
02601 
02602   public: void Clear();
02603 
02604   public: char rawText[SPEECH_RECOGNITION_TEXT_LEN];
02605 
02606   // Just estimating that no more than 20 words will be spoken between updates.
02607   // Assuming that the longest word is <= 30 characters.
02608   public: char words[20][30]; 
02609   public: int wordCount;
02610 };
02611 
02615 class SimulationProxy : public ClientProxy
02616 {
02617  public: 
02618 
02620   SimulationProxy (PlayerClient* pc, unsigned short index,
02621                    unsigned char access = 'c')
02622     : ClientProxy(pc,PLAYER_SIMULATION_CODE,index,access) 
02623     {}
02624   
02626   ~SimulationProxy()
02627     {}
02628   
02631   int SetPose2D( char* identifier, double x, double y, double a );
02632 
02635   int GetPose2D( char* identifier, double& x, double& y, double& a );
02636 
02637   virtual void FillData(player_msghdr_t hdr, const char* buffer);  
02638   virtual void Print();
02639 };         
02640 
02644 class LogProxy : public ClientProxy
02645 {
02646  public: 
02648   LogProxy (PlayerClient* pc, unsigned short index,
02649             unsigned char access = 'c')
02650           : ClientProxy(pc,PLAYER_LOG_CODE,index,access) {}
02651   
02653   ~LogProxy() {}
02654 
02657   int type;
02658 
02660   int state;
02661 
02664   int LogProxy::GetState();
02665 
02668   int LogProxy::SetWriteState(int state);
02669 
02672   int LogProxy::SetReadState(int state);
02673 
02675   int LogProxy::Rewind();
02676 
02679   int LogProxy::SetFilename(const char* fname);
02680   
02681   virtual void FillData(player_msghdr_t hdr, const char* buffer);  
02682   virtual void Print();
02683 };         
02684 
02685 
02690 #endif
02691            

Generated on Tue May 3 14:15:35 2005 for Player by doxygen 1.3.6