playerc++.h
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  *
00024  *  This library is free software; you can redistribute it and/or
00025  *  modify it under the terms of the GNU Lesser General Public
00026  *  License as published by the Free Software Foundation; either
00027  *  version 2.1 of the License, or (at your option) any later version.
00028  *
00029  *  This library is distributed in the hope that it will be useful,
00030  *  but WITHOUT ANY WARRANTY; without even the implied warranty of
00031  *  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU
00032  *  Lesser General Public License for more details.
00033  *
00034  *  You should have received a copy of the GNU Lesser General Public
00035  *  License along with this library; if not, write to the Free Software
00036  *  Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA
00037  *
00038  ********************************************************************/
00039 
00040 /***************************************************************************
00041  * Desc: Player v2.0 C++ client
00042  * Authors: Brad Kratochvil, Toby Collett
00043  *
00044  * Date: 23 Sep 2005
00045  # CVS: $Id: playerc++.h 9037 2011-02-16 17:40:39Z jpgr87 $
00046  **************************************************************************/
00047 
00048 
00049 #ifndef PLAYERCC_H
00050 #define PLAYERCC_H
00051 
00052 #include <cstddef>
00053 #include <cmath>
00054 #include <string>
00055 #include <list>
00056 #include <vector>
00057 #include <cstring>
00058 
00059 #include "libplayerc/playerc.h"
00060 #include "libplayerc++/utility.h"
00061 #include "libplayerc++/playerclient.h"
00062 #include "libplayerc++/playererror.h"
00063 #include "libplayerc++/clientproxy.h"
00064 #include "libplayerinterface/interface_util.h"
00065 
00066 #if defined (WIN32)
00067   #if defined (PLAYER_STATIC)
00068     #define PLAYERCC_EXPORT
00069   #elif defined (playerc___EXPORTS)
00070     #define PLAYERCC_EXPORT    __declspec (dllexport)
00071   #else
00072     #define PLAYERCC_EXPORT    __declspec (dllimport)
00073   #endif
00074 #else
00075   #define PLAYERCC_EXPORT
00076 #endif
00077 
00078 // Don't think we need to include these here
00079 /*
00080 #ifdef HAVE_BOOST_SIGNALS
00081   #include <boost/signal.hpp>
00082   #include <boost/bind.hpp>
00083 #endif
00084 
00085 #ifdef HAVE_BOOST_THREAD
00086   #include <boost/thread/mutex.hpp>
00087   #include <boost/thread/thread.hpp>
00088   #include <boost/thread/xtime.hpp>
00089 #endif
00090 */
00091 
00092 namespace PlayerCc
00093 {
00094 
00095 // /**
00096 // * The @p SomethingProxy class is a template for adding new subclasses of
00097 // * ClientProxy.  You need to have at least all of the following:
00098 // */
00099 // class SomethingProxy : public ClientProxy
00100 // {
00101 //
00102 //   private:
00103 //
00104 //     // Subscribe
00105 //     void Subscribe(uint32_t aIndex);
00106 //     // Unsubscribe
00107 //     void Unsubscribe();
00108 //
00109 //     // libplayerc data structure
00110 //     playerc_something_t *mDevice;
00111 //
00112 //   public:
00113 //     // Constructor
00114 //     SomethingProxy(PlayerClient *aPc, uint32_t aIndex=0);
00115 //     // Destructor
00116 //     ~SomethingProxy();
00117 //
00118 // };
00119 
00131 // ==============================================================
00132 //
00133 // These are alphabetized, please keep them that way!!!
00134 //
00135 // ==============================================================
00136 
00141 class PLAYERCC_EXPORT ActArrayProxy : public ClientProxy
00142 {
00143   private:
00144 
00145    void Subscribe(uint32_t aIndex);
00146    void Unsubscribe();
00147 
00148    // libplayerc data structure
00149    playerc_actarray_t *mDevice;
00150 
00151   public:
00152 
00154     ActArrayProxy(PlayerClient *aPc, uint32_t aIndex=0);
00156     ~ActArrayProxy();
00157 
00160     void RequestGeometry(void);
00161 
00163     void SetPowerConfig(bool aVal);
00165     void SetBrakesConfig(bool aVal);
00167     void SetSpeedConfig(uint32_t aJoint, float aSpeed);
00169     void SetAccelerationConfig(uint32_t aJoint, float aAcc);
00170 
00172     void MoveTo(uint32_t aJoint, float aPos);
00174     void MoveToMulti(std::vector<float> aPos);
00176     void MoveAtSpeed(uint32_t aJoint, float aSpeed);
00178     void MoveAtSpeedMulti(std::vector<float> aSpeed);
00180     void MoveHome(int aJoint);
00182     void SetActuatorCurrent(uint32_t aJoint, float aCurrent);
00184     void SetActuatorCurrentMulti(std::vector<float> aCurrent);
00185 
00187     uint32_t GetCount(void) const { return GetVar(mDevice->actuators_count); }
00189     player_actarray_actuator_t GetActuatorData(uint32_t aJoint) const;
00191     player_actarray_actuatorgeom_t GetActuatorGeom(uint32_t aJoint) const;
00193     player_point_3d_t GetBasePos(void) const { return GetVar(mDevice->base_pos); }
00195     player_orientation_3d_t GetBaseOrientation(void) const { return GetVar(mDevice->base_orientation); }
00196 
00197 
00202     player_actarray_actuator_t operator [](uint32_t aJoint)
00203       { return(GetActuatorData(aJoint)); }
00204 };
00205 
00209 class PLAYERCC_EXPORT AioProxy : public ClientProxy
00210 {
00211   private:
00212 
00213     void Subscribe(uint32_t aIndex);
00214     void Unsubscribe();
00215 
00216     // libplayerc data structure
00217     playerc_aio_t *mDevice;
00218 
00219   public:
00220 
00222     AioProxy (PlayerClient *aPc, uint32_t aIndex=0);
00224     ~AioProxy();
00225 
00227     uint32_t GetCount() const { return(GetVar(mDevice->voltages_count)); };
00228 
00230     double GetVoltage(uint32_t aIndex)  const
00231       { return(GetVar(mDevice->voltages[aIndex])); };
00232 
00234     void SetVoltage(uint32_t aIndex, double aVoltage);
00235 
00240     double operator [](uint32_t aIndex) const
00241       { return GetVoltage(aIndex); }
00242 
00243 };
00244 
00245 
00249 class PLAYERCC_EXPORT AudioProxy : public ClientProxy
00250 {
00251 
00252   private:
00253 
00254     void Subscribe(uint32_t aIndex);
00255     void Unsubscribe();
00256 
00257     // libplayerc data structure
00258     playerc_audio_t *mDevice;
00259 
00260   public:
00261 
00263     AudioProxy(PlayerClient *aPc, uint32_t aIndex=0);
00265     ~AudioProxy();
00266 
00268     uint32_t GetMixerDetailsCount() const {return(GetVar(mDevice->channel_details_list.details_count));};
00270     player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const  {return(GetVar(mDevice->channel_details_list.details[aIndex]));};
00272     uint32_t GetDefaultOutputChannel() const  {return(GetVar(mDevice->channel_details_list.default_output));};
00274     uint32_t GetDefaultInputChannel() const {return(GetVar(mDevice->channel_details_list.default_input));};
00275 
00277     uint32_t GetWavDataLength() const {return(GetVar(mDevice->wav_data.data_count));};
00282     void GetWavData(uint8_t* aData) const
00283       {
00284         return GetVarByRef(mDevice->wav_data.data,
00285                            mDevice->wav_data.data+GetWavDataLength(),
00286                            aData);
00287       };
00288 
00290     uint32_t GetSeqCount() const {return(GetVar(mDevice->seq_data.tones_count));};
00292     player_audio_seq_item_t GetSeqItem(int aIndex) const  {return(GetVar(mDevice->seq_data.tones[aIndex]));};
00293 
00295     uint32_t GetChannelCount() const {return(GetVar(mDevice->mixer_data.channels_count));};
00297     player_audio_mixer_channel_t GetChannel(int aIndex) const  {return(GetVar(mDevice->mixer_data.channels[aIndex]));};
00299     uint32_t GetState(void) const {return(GetVar(mDevice->state));};
00300 
00301 
00302 
00304     void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
00305 
00307     void SetWavStremRec(bool aState);
00308 
00310     void PlaySample(int aIndex);
00311 
00313     void PlaySeq(player_audio_seq_t * aTones);
00314 
00316     void SetMultMixerLevels(player_audio_mixer_channel_list_t * aLevels);
00317 
00319     void SetMixerLevel(uint32_t index, float amplitude, uint8_t active);
00320 
00323     void RecordWav();
00324 
00326     void LoadSample(int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
00327 
00330     void GetSample(int aIndex);
00331 
00333     void RecordSample(int aIndex, uint32_t aLength);
00334 
00337     void GetMixerLevels();
00338 
00341     void GetMixerDetails();
00342 
00343 };
00344 
00352 class PLAYERCC_EXPORT BlackBoardProxy : public ClientProxy
00353 {
00354   private:
00355     void Subscribe(uint32_t aIndex);
00356     void Unsubscribe();
00357 
00358     // libplayerc data structure
00359     playerc_blackboard_t *mDevice;
00360 
00361   public:
00363         BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0);
00365         ~BlackBoardProxy();
00367         player_blackboard_entry_t *SubscribeToKey(const char *key, const char* group = "");
00369         void UnsubscribeFromKey(const char *key, const char* group = "");
00371         void SubscribeToGroup(const char* key);
00373         void UnsubscribeFromGroup(const char* group);
00375         void SetEntry(const player_blackboard_entry_t &entry);
00377         player_blackboard_entry_t *GetEntry(const char* key, const char* group);
00379         void SetEventHandler(void (*on_blackboard_event)(playerc_blackboard_t *, player_blackboard_entry_t));
00380 };
00381 
00382 // /**
00383 // The @p BlinkenlightProxy class is used to enable and disable
00384 // a flashing indicator light, and to set its period, via a @ref
00385 // interface_blinkenlight device */
00386 // class PLAYERCC_EXPORT BlinkenLightProxy : public ClientProxy
00387 // {
00388 //   private:
00389 //
00390 //     void Subscribe(uint32_t aIndex);
00391 //     void Unsubscribe();
00392 //
00393 //     // libplayerc data structure
00394 //     playerc_blinkenlight_t *mDevice;
00395 //
00396 //   public:
00397 //     /** Constructor.
00398 //         Leave the access field empty to start unconnected.
00399 //     */
00400 //     BlinkenLightProxy(PlayerClient *aPc, uint32_t aIndex=0);
00401 //     ~BlinkenLightProxy();
00402 //
00403 //     // true: indicator light enabled, false: disabled.
00404 //     bool GetEnable();
00405 //
00406 //     /** The current period (one whole on/off cycle) of the blinking
00407 //         light. If the period is zero and the light is enabled, the light
00408 //         is on.
00409 //     */
00410 //     void SetPeriod(double aPeriod);
00411 //
00412 //     /** Set the state of the indicator light. A period of zero means
00413 //         the light will be unblinkingly on or off. Returns 0 on
00414 //         success, else -1.
00415 //       */
00416 //     void SetEnable(bool aSet);
00417 // };
00418 
00425 class PLAYERCC_EXPORT BlobfinderProxy : public ClientProxy
00426 {
00427   private:
00428 
00429     void Subscribe(uint32_t aIndex);
00430     void Unsubscribe();
00431 
00432     // libplayerc data structure
00433     playerc_blobfinder_t *mDevice;
00434 
00435   public:
00437     BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0);
00439     ~BlobfinderProxy();
00440 
00442     uint32_t GetCount() const { return GetVar(mDevice->blobs_count); };
00444     playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
00445       { return GetVar(mDevice->blobs[aIndex]);};
00446 
00448     uint32_t GetWidth() const { return GetVar(mDevice->width); };
00450     uint32_t GetHeight() const { return GetVar(mDevice->height); };
00451 
00456     playerc_blobfinder_blob_t operator [](uint32_t aIndex) const
00457       { return(GetBlob(aIndex)); }
00458 
00459 /*
00460     // Set the color to be tracked
00461     void SetTrackingColor(uint32_t aReMin=0,   uint32_t aReMax=255, uint32_t aGrMin=0,
00462                           uint32_t aGrMax=255, uint32_t aBlMin=0,   uint32_t aBlMax=255);
00463     void SetImagerParams(int aContrast, int aBrightness,
00464                          int aAutogain, int aColormode);
00465     void SetContrast(int aC);
00466     void SetColorMode(int aM);
00467     void SetBrightness(int aB);
00468     void SetAutoGain(int aG);*/
00469 
00470 };
00471 
00476 class PLAYERCC_EXPORT BumperProxy : public ClientProxy
00477 {
00478 
00479   private:
00480 
00481     void Subscribe(uint32_t aIndex);
00482     void Unsubscribe();
00483 
00484     // libplayerc data structure
00485     playerc_bumper_t *mDevice;
00486 
00487   public:
00488 
00490     BumperProxy(PlayerClient *aPc, uint32_t aIndex=0);
00492     ~BumperProxy();
00493 
00495     uint32_t GetCount() const { return GetVar(mDevice->bumper_count); };
00496 
00498     uint32_t IsBumped(uint32_t aIndex) const
00499       { return GetVar(mDevice->bumpers[aIndex]); };
00500 
00502     bool IsAnyBumped();
00503 
00505     void RequestBumperConfig();
00506 
00508     uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
00509 
00511     player_bumper_define_t GetPose(uint32_t aIndex) const
00512       { return GetVar(mDevice->poses[aIndex]); };
00513 
00518     bool operator [](uint32_t aIndex) const
00519           { return IsBumped(aIndex) != 0 ? true : false; }
00520 
00521 };
00522 
00526 class PLAYERCC_EXPORT CameraProxy : public ClientProxy
00527 {
00528 
00529   private:
00530 
00531     virtual void Subscribe(uint32_t aIndex);
00532     virtual void Unsubscribe();
00533 
00534     // libplayerc data structure
00535     playerc_camera_t *mDevice;
00536 
00537     std::string mPrefix;
00538     int mFrameNo;
00539 
00540   public:
00541 
00543     CameraProxy (PlayerClient *aPc, uint32_t aIndex=0);
00544 
00546     virtual ~CameraProxy();
00547 
00551     void SaveFrame(const std::string aPrefix, uint32_t aWidth=4);
00552 
00554     void Decompress();
00555 
00557     uint32_t GetDepth() const { return GetVar(mDevice->bpp); };
00558 
00560     uint32_t GetWidth() const { return GetVar(mDevice->width); };
00561 
00563     uint32_t GetHeight() const { return GetVar(mDevice->height); };
00564 
00571     uint32_t GetFormat() const { return GetVar(mDevice->format); };
00572 
00574     uint32_t GetImageSize() const { return GetVar(mDevice->image_count); };
00575 
00580     void GetImage(uint8_t* aImage) const
00581       {
00582         return GetVarByRef(mDevice->image,
00583                            mDevice->image+GetVar(mDevice->image_count),
00584                            aImage);
00585       };
00586 
00591     uint32_t GetCompression() const { return GetVar(mDevice->compression); };
00592 
00593 };
00594 
00595 
00600 class PLAYERCC_EXPORT DioProxy : public ClientProxy
00601 {
00602   private:
00603 
00604     void Subscribe(uint32_t aIndex);
00605     void Unsubscribe();
00606 
00607     // libplayerc data structure
00608     playerc_dio_t *mDevice;
00609 
00610   public:
00612     DioProxy(PlayerClient *aPc, uint32_t aIndex=0);
00614     ~DioProxy();
00615 
00617     uint32_t GetCount() const { return GetVar(mDevice->count); };
00618 
00620     uint32_t GetDigin() const { return GetVar(mDevice->digin); };
00621 
00623     bool GetInput(uint32_t aIndex) const;
00624 
00626     void SetOutput(uint32_t aCount, uint32_t aDigout);
00627 
00632     uint32_t operator [](uint32_t aIndex) const
00633       { return GetInput(aIndex); }
00634 };
00635 
00641 class PLAYERCC_EXPORT FiducialProxy : public ClientProxy
00642 {
00643   private:
00644     void Subscribe(uint32_t aIndex);
00645     void Unsubscribe();
00646 
00647     // libplayerc data structure
00648     playerc_fiducial_t *mDevice;
00649 
00650   public:
00652     FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0);
00654     ~FiducialProxy();
00655 
00657     uint32_t GetCount() const { return GetVar(mDevice->fiducials_count); };
00658 
00660     player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const
00661       { return GetVar(mDevice->fiducials[aIndex]);};
00662 
00664     player_pose3d_t GetSensorPose() const
00665       { return GetVar(mDevice->fiducial_geom.pose);};
00666 
00668     player_bbox3d_t GetSensorSize() const
00669       { return GetVar(mDevice->fiducial_geom.size);};
00670 
00672     player_bbox2d_t GetFiducialSize() const
00673       { return GetVar(mDevice->fiducial_geom.fiducial_size);};
00674 
00676     void RequestGeometry();
00677 
00682     player_fiducial_item_t operator [](uint32_t aIndex) const
00683       { return GetFiducialItem(aIndex); }
00684 };
00685 
00689 class PLAYERCC_EXPORT GpsProxy : public ClientProxy
00690 {
00691 
00692   private:
00693 
00694     void Subscribe(uint32_t aIndex);
00695     void Unsubscribe();
00696 
00697     // libplayerc data structure
00698     playerc_gps_t *mDevice;
00699 
00700   public:
00701 
00703     GpsProxy(PlayerClient *aPc, uint32_t aIndex=0);
00705     ~GpsProxy();
00706 
00708     double GetLatitude() const { return GetVar(mDevice->lat); };
00709     double GetLongitude() const { return GetVar(mDevice->lon); };
00710 
00712     double GetAltitude() const { return GetVar(mDevice->alt); };
00713 
00715     uint32_t GetSatellites() const { return GetVar(mDevice->sat_count); };
00716 
00718     uint32_t GetQuality() const { return GetVar(mDevice->quality); };
00719 
00721     double GetHdop() const { return GetVar(mDevice->hdop); };
00722 
00724     double GetVdop() const { return GetVar(mDevice->vdop); };
00725 
00727     double GetUtmEasting() const { return GetVar(mDevice->utm_e); };
00728     double GetUtmNorthing() const { return GetVar(mDevice->utm_n); };
00729 
00731     double GetTime() const { return GetVar(mDevice->utc_time); };
00732 
00734     double GetErrHorizontal() const { return GetVar(mDevice->err_horz); };
00735     double GetErrVertical() const { return GetVar(mDevice->err_vert); };
00736 };
00737 
00745 class PLAYERCC_EXPORT Graphics2dProxy : public ClientProxy
00746 {
00747 
00748   private:
00749 
00750     // Subscribe
00751     void Subscribe(uint32_t aIndex);
00752     // Unsubscribe
00753     void Unsubscribe();
00754 
00755     // libplayerc data structure
00756     playerc_graphics2d_t *mDevice;
00757 
00758   public:
00760     Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
00762     ~Graphics2dProxy();
00763 
00765     void Color(player_color_t col);
00766 
00768     void Color(uint8_t red,  uint8_t green,  uint8_t blue,  uint8_t alpha);
00769 
00771     void Clear(void);
00772 
00774     void DrawPoints(player_point_2d_t pts[], int count);
00775 
00777     void DrawPolygon(player_point_2d_t pts[],
00778                      int count,
00779                      bool filled,
00780                      player_color_t fill_color);
00781 
00783     void DrawPolyline(player_point_2d_t pts[], int count);
00784 
00785 
00787     void DrawMultiline(player_point_2d_t pts[], int count);
00788 };
00789 
00795 class PLAYERCC_EXPORT Graphics3dProxy : public ClientProxy
00796 {
00797 
00798   private:
00799 
00800     // Subscribe
00801     void Subscribe(uint32_t aIndex);
00802     // Unsubscribe
00803     void Unsubscribe();
00804 
00805     // libplayerc data structure
00806     playerc_graphics3d_t *mDevice;
00807 
00808   public:
00810     Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
00812     ~Graphics3dProxy();
00813 
00815     void Color(player_color_t col);
00816 
00818     void Color(uint8_t red,  uint8_t green,  uint8_t blue,  uint8_t alpha);
00819 
00821     void Clear(void);
00822 
00824     void Draw(player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count);
00825 
00826 };
00827 
00832 class PLAYERCC_EXPORT GripperProxy : public ClientProxy
00833 {
00834 
00835   private:
00836 
00837     void Subscribe(uint32_t aIndex);
00838     void Unsubscribe();
00839 
00840     // libplayerc data structure
00841     playerc_gripper_t *mDevice;
00842 
00843   public:
00844 
00846     GripperProxy(PlayerClient *aPc, uint32_t aIndex=0);
00848     ~GripperProxy();
00849 
00852     void RequestGeometry(void);
00853 
00855     uint32_t GetState() const { return GetVar(mDevice->state); };
00857     uint32_t GetBeams() const { return GetVar(mDevice->beams); };
00859     player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
00861     player_bbox3d_t GetOuterSize() const { return GetVar(mDevice->outer_size); };
00863     player_bbox3d_t GetInnerSize() const { return GetVar(mDevice->inner_size); };
00865     uint32_t GetNumBeams() const { return GetVar(mDevice->num_beams); };
00867     uint32_t GetCapacity() const { return GetVar(mDevice->capacity); };
00869     uint32_t GetStored() const { return GetVar(mDevice->stored); };
00870 
00872     void Open();
00874     void Close();
00876     void Stop();
00878     void Store();
00880     void Retrieve();
00881 };
00882 
00885 class PLAYERCC_EXPORT HealthProxy : public ClientProxy
00886 {
00887 
00888   private:
00889 
00890     void Subscribe(uint32_t aIndex);
00891     void Unsubscribe();
00892 
00893     // libplayerc data structure
00894     playerc_health_t *mDevice;
00895 
00896   public:
00898     HealthProxy(PlayerClient *aPc, uint32_t aIndex=0);
00900     ~HealthProxy();
00901 
00903     float GetIdleCPU();
00904 
00906     float GetSystemCPU();
00907 
00909     float GetUserCPU();
00910 
00912     int64_t GetMemTotal();
00913 
00915     int64_t GetMemUsed();
00916 
00918     int64_t GetMemFree();
00919 
00921     int64_t GetSwapTotal();
00922 
00924     int64_t GetSwapUsed();
00925 
00927     int64_t GetSwapFree();
00928 
00930     float GetPercMemUsed();
00931 
00933     float GetPercSwapUsed();
00934 
00936     float GetPercTotalUsed();
00937 };
00938 
00939 
00940 
00945 class PLAYERCC_EXPORT ImuProxy : public ClientProxy
00946 {
00947   private:
00948     void Subscribe(uint32_t aIndex);
00949     void Unsubscribe();
00950 
00951     // libplayerc data structure
00952     playerc_imu_t *mDevice;
00953 
00954   public:
00955 
00957     ImuProxy(PlayerClient *aPc, uint32_t aIndex=0);
00959     ~ImuProxy();
00960 
00962     player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
00963     
00965     float GetXAccel();
00967     float GetYAccel();
00969     float GetZAccel();
00971     float GetXGyro();
00973     float GetYGyro();
00975     float GetZGyro();
00977     float GetXMagn();
00979     float GetYMagn();
00981     float GetZMagn();
00982 
00984     player_imu_data_calib_t GetRawValues() const
00985     { return GetVar(mDevice->calib_data); };
00986 
00988     void SetDatatype(int aDatatype);
00989 
00991     void ResetOrientation(int aValue);
00992 
00993 
00994 };
00995 
00996 
01001 class PLAYERCC_EXPORT IrProxy : public ClientProxy
01002 {
01003 
01004   private:
01005 
01006     void Subscribe(uint32_t aIndex);
01007     void Unsubscribe();
01008 
01009     // libplayerc data structure
01010     playerc_ir_t *mDevice;
01011 
01012   public:
01013 
01015     IrProxy(PlayerClient *aPc, uint32_t aIndex=0);
01017     ~IrProxy();
01018 
01020     uint32_t GetCount() const { return GetVar(mDevice->data.ranges_count); };
01022     double GetRange(uint32_t aIndex) const
01023       { return GetVar(mDevice->data.ranges[aIndex]); };
01025     double GetVoltage(uint32_t aIndex) const
01026       { return GetVar(mDevice->data.voltages[aIndex]); };
01028     uint32_t GetPoseCount() const { return GetVar(mDevice->poses.poses_count); };
01030     player_pose3d_t GetPose(uint32_t aIndex) const
01031       {return GetVar(mDevice->poses.poses[aIndex]);};
01032 
01034     void RequestGeom();
01035 
01040     double operator [](uint32_t aIndex) const
01041       { return GetRange(aIndex); }
01042 
01043 };
01044 
01050 class PLAYERCC_EXPORT LaserProxy : public ClientProxy
01051 {
01052   private:
01053 
01054     void Subscribe(uint32_t aIndex);
01055     void Unsubscribe();
01056 
01057     // libplayerc data structure
01058     playerc_laser_t *mDevice;
01059 
01060     // local storage of config
01061     double min_angle, max_angle, scan_res, range_res, scanning_frequency;
01062     bool intensity;
01063 
01064   public:
01065 
01067     LaserProxy(PlayerClient *aPc, uint32_t aIndex=0);
01069     ~LaserProxy();
01070 
01072     uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
01073 
01075     double GetMaxRange() const { return GetVar(mDevice->max_range); };
01076 
01078     double GetScanRes() const { return GetVar(mDevice->scan_res); };
01079 
01081     double GetRangeRes() const { return GetVar(mDevice->range_res); };
01082 
01084     double GetScanningFrequency() const { return GetVar(mDevice->scanning_frequency); };
01085 
01087     double GetMinAngle() const { return GetVar(mDevice->scan_start); };
01089     double GetMaxAngle() const
01090     {
01091       scoped_lock_t lock(mPc->mMutex);
01092       return mDevice->scan_start + (mDevice->scan_count - 1)*mDevice->scan_res;
01093     };
01094 
01096     double GetConfMinAngle() const { return min_angle; };
01098     double GetConfMaxAngle() const { return max_angle; };
01099 
01101     bool IntensityOn() const { return GetVar(mDevice->intensity_on) != 0 ? true : false; };
01102 
01103 //    // Scan data (polar): range (m) and bearing (radians)
01104 //    double GetScan(uint32_t aIndex) const
01105 //      { return GetVar(mDevice->scan[aIndex]); };
01106 
01108     player_point_2d_t GetPoint(uint32_t aIndex) const
01109       { return GetVar(mDevice->point[aIndex]); };
01110 
01111 
01113     double GetRange(uint32_t aIndex) const
01114       { return GetVar(mDevice->ranges[aIndex]); };
01115 
01117     double GetBearing(uint32_t aIndex) const
01118       { return GetVar(mDevice->scan[aIndex][1]); };
01119 
01120 
01122     int GetIntensity(uint32_t aIndex) const
01123       { return GetVar(mDevice->intensity[aIndex]); };
01124 
01126     int GetID() const
01127       { return GetVar(mDevice->laser_id); };
01128 
01129 
01138     void Configure(double aMinAngle,
01139                    double aMaxAngle,
01140                    uint32_t aScanRes,
01141                    uint32_t aRangeRes,
01142                    bool aIntensity,
01143                    double aScanningFrequency);
01144 
01147     void RequestConfigure();
01148 
01150     void RequestID();
01151 
01154     void RequestGeom();
01155 
01158     player_pose3d_t GetPose()
01159     {
01160       player_pose3d_t p;
01161       scoped_lock_t lock(mPc->mMutex);
01162 
01163       p.px = mDevice->pose[0];
01164       p.py = mDevice->pose[1];
01165       p.pyaw = mDevice->pose[2];
01166       return(p);
01167     }
01168 
01171     player_pose3d_t GetRobotPose()
01172     {
01173       player_pose3d_t p;
01174       scoped_lock_t lock(mPc->mMutex);
01175 
01176       p.px = mDevice->robot_pose[0];
01177       p.py = mDevice->robot_pose[1];
01178       p.pyaw = mDevice->robot_pose[2];
01179       return(p);
01180     }
01181 
01183     player_bbox3d_t GetSize()
01184     {
01185       player_bbox3d_t b;
01186       scoped_lock_t lock(mPc->mMutex);
01187 
01188       b.sl = mDevice->size[0];
01189       b.sw = mDevice->size[1];
01190       return(b);
01191     }
01192 
01194     double GetMinLeft() const
01195       { return GetVar(mDevice->min_left); };
01196 
01198     double GetMinRight() const
01199       { return GetVar(mDevice->min_right); };
01200 
01202     double MinLeft () const
01203       { return GetMinLeft(); }
01204 
01206     double MinRight () const
01207       { return GetMinRight(); }
01208 
01213     double operator [] (uint32_t index) const
01214       { return GetRange(index);}
01215 
01216 };
01217 
01218 
01223 class PLAYERCC_EXPORT LimbProxy : public ClientProxy
01224 {
01225   private:
01226 
01227     void Subscribe(uint32_t aIndex);
01228     void Unsubscribe();
01229 
01230    // libplayerc data structure
01231     playerc_limb_t *mDevice;
01232 
01233   public:
01234 
01236     LimbProxy(PlayerClient *aPc, uint32_t aIndex=0);
01238     ~LimbProxy();
01239 
01242     void RequestGeometry(void);
01243 
01245     void SetPowerConfig(bool aVal);
01247     void SetBrakesConfig(bool aVal);
01249     void SetSpeedConfig(float aSpeed);
01250 
01252     void MoveHome(void);
01254     void Stop(void);
01256     void SetPose(float aPX, float aPY, float aPZ,
01257                  float aAX, float aAY, float aAZ,
01258                  float aOX, float aOY, float aOZ);
01260     void SetPosition(float aX, float aY, float aZ);
01263     void VectorMove(float aX, float aY, float aZ, float aLength);
01264 
01266     player_limb_data_t GetData(void) const;
01268     player_limb_geom_req_t GetGeom(void) const;
01269 };
01270 
01271 
01277 class PLAYERCC_EXPORT LinuxjoystickProxy : public ClientProxy
01278 {
01279   private:
01280 
01281     void Subscribe(uint32_t aIndex);
01282     void Unsubscribe();
01283 
01284     // libplayerc data structure
01285     playerc_joystick_t *mDevice;
01286 
01287   public:
01288     // Constructor
01289     LinuxjoystickProxy(PlayerClient *aPc, uint32_t aIndex=0);
01290     // Destructor
01291     ~LinuxjoystickProxy();
01292 
01294     uint32_t GetButtons() const { return GetVar(mDevice->buttons); };
01295 
01297     double GetAxes(uint32_t aIndex) const
01298       { if (GetVar(mDevice->axes_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->pos[aIndex]); };
01301     double operator [] (uint32_t aIndex) const { return GetAxes(aIndex); }
01302 
01304     uint32_t GetAxesCount() const { return GetVar(mDevice->axes_count); };
01305 
01307 //    player_pose3d_t GetPose(uint32_t aIndex) const
01308 //      { return GetVar(mDevice->poses[aIndex]); };
01309 
01310     // Enable/disable the joysticks.
01311     // Set @p state to 1 to enable, 0 to disable.
01312     // Note that when joysticks are disabled the client will still receive joystick
01313     // data, but the ranges will always be the last value read from the joysticks
01314     // before they were disabled.
01315     //void SetEnable(bool aEnable);
01316 
01318 //    void RequestGeom();
01319 };
01320 
01321 
01327 class PLAYERCC_EXPORT LocalizeProxy : public ClientProxy
01328 {
01329 
01330   private:
01331 
01332     void Subscribe(uint32_t aIndex);
01333     void Unsubscribe();
01334 
01335     // libplayerc data structure
01336     playerc_localize_t *mDevice;
01337 
01338   public:
01339 
01341     LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0);
01343     ~LocalizeProxy();
01344 
01346     // @todo should these be in a player_pose_t?
01347     uint32_t GetMapSizeX() const { return GetVar(mDevice->map_size_x); };
01349     uint32_t GetMapSizeY() const { return GetVar(mDevice->map_size_y); };
01350 
01351     // @todo should these be in a player_pose_t?
01353     uint32_t GetMapTileX() const { return GetVar(mDevice->map_tile_x); };
01355     uint32_t GetMapTileY() const { return GetVar(mDevice->map_tile_y); };
01356 
01358     double GetMapScale() const { return GetVar(mDevice->map_scale); };
01359 
01360     // Map data (empty = -1, unknown = 0, occupied = +1)
01361     // is this still needed?  if so,
01362     //void GetMapCells(uint8_t* aCells) const
01363     //{
01364     //  return GetVarByRef(mDevice->map_cells,
01365     //                     mDevice->image+GetVar(mDevice->??map_cell_cout??),
01366     //                     aCells);
01367     //};
01368 
01370     uint32_t GetPendingCount() const { return GetVar(mDevice->pending_count); };
01371 
01373     uint32_t GetHypothCount() const { return GetVar(mDevice->hypoth_count); };
01374 
01376     player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
01377       { return GetVar(mDevice->hypoths[aIndex]); };
01378 
01380     int GetParticles()
01381       { return playerc_localize_get_particles(mDevice); }
01382 
01384     player_pose2d_t GetParticlePose(int index) const;
01385 
01387     void SetPose(double pose[3], double cov[6]);
01388 
01390     uint32_t GetNumHypoths() const { return GetVar(mDevice->hypoth_count); };
01391 
01394     uint32_t GetNumParticles() const { return GetVar(mDevice->num_particles); };
01395 };
01396 
01397 
01401 class PLAYERCC_EXPORT LogProxy : public ClientProxy
01402 {
01403   private:
01404 
01405     void Subscribe(uint32_t aIndex);
01406     void Unsubscribe();
01407 
01408     // libplayerc data structure
01409     playerc_log_t *mDevice;
01410 
01411   public:
01413     LogProxy(PlayerClient *aPc, uint32_t aIndex=0);
01414 
01416     ~LogProxy();
01417 
01420     int GetType() const { return GetVar(mDevice->type); };
01421 
01423     int GetState() const { return GetVar(mDevice->state); };
01424 
01426     void QueryState();
01427 
01430     void SetState(int aState);
01431 
01433     void SetWriteState(int aState);
01434 
01436     void SetReadState(int aState);
01437 
01439     void Rewind();
01440 
01442     void SetFilename(const std::string aFilename);
01443 };
01444 
01448 class PLAYERCC_EXPORT MapProxy : public ClientProxy
01449 {
01450   private:
01451 
01452     void Subscribe(uint32_t aIndex);
01453     void Unsubscribe();
01454 
01455     // libplayerc data structure
01456     playerc_map_t *mDevice;
01457 
01458   public:
01460     MapProxy(PlayerClient *aPc, uint32_t aIndex=0);
01461 
01463     ~MapProxy();
01464 
01466     void RequestMap();
01467 
01469     int GetCellIndex(int x, int y) const
01470     { return y*GetWidth() + x; };
01471 
01473     int8_t GetCell(int x, int y) const
01474     { return GetVar(mDevice->cells[GetCellIndex(x,y)]); };
01475 
01477     double GetResolution() const { return GetVar(mDevice->resolution); };
01478 
01480     //    @todo should this be returned as a player_size_t?
01481     uint32_t GetWidth() const { return GetVar(mDevice->width); };
01483     // @todo should this be returned as a player_size_t?
01484     uint32_t GetHeight() const { return GetVar(mDevice->height); };
01485 
01486     double GetOriginX() const { return GetVar(mDevice->origin[0]); };
01487     double GetOriginY() const { return GetVar(mDevice->origin[1]); };
01488 
01490     int8_t GetDataRange() const { return GetVar(mDevice->data_range); };
01491 
01493     void GetMap(int8_t* aMap) const
01494     {
01495       return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->cells),
01496                          reinterpret_cast<int8_t*>(mDevice->cells+GetWidth()*GetHeight()),
01497                          aMap);
01498     };
01499 };
01500 
01506 class PLAYERCC_EXPORT OpaqueProxy : public ClientProxy
01507 {
01508 
01509   private:
01510 
01511     void Subscribe(uint32_t aIndex);
01512     void Unsubscribe();
01513 
01514     // libplayerc data structure
01515     playerc_opaque_t *mDevice;
01516 
01517   public:
01518 
01520     OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0);
01522     ~OpaqueProxy();
01523 
01525     uint32_t GetCount() const { return GetVar(mDevice->data_count); };
01526 
01528     void GetData(uint8_t* aDest) const
01529       {
01530         return GetVarByRef(mDevice->data,
01531                            mDevice->data+GetVar(mDevice->data_count),
01532                            aDest);
01533       };
01534 
01536     void SendCmd(player_opaque_data_t* aData);
01537 
01539     int SendReq(player_opaque_data_t* aRequest);
01540 
01541 };
01542 
01546 class PLAYERCC_EXPORT PlannerProxy : public ClientProxy
01547 {
01548 
01549   private:
01550 
01551     void Subscribe(uint32_t aIndex);
01552     void Unsubscribe();
01553 
01554     // libplayerc data structure
01555     playerc_planner_t *mDevice;
01556 
01557   public:
01558 
01560     PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0);
01562     ~PlannerProxy();
01563 
01565     void SetGoalPose(double aGx, double aGy, double aGa);
01566 
01569     void RequestWaypoints();
01570 
01573     void SetEnable(bool aEnable);
01574 
01576     uint32_t GetPathValid() const { return GetVar(mDevice->path_valid); };
01577 
01579     uint32_t GetPathDone() const { return GetVar(mDevice->path_done); };
01580 
01583     double GetPx() const { return GetVar(mDevice->px); };
01586     double GetPy() const { return GetVar(mDevice->py); };
01589     double GetPa() const { return GetVar(mDevice->pa); };
01590 
01592     player_pose2d_t GetPose() const
01593     {
01594       player_pose2d_t p;
01595       scoped_lock_t lock(mPc->mMutex);
01596       p.px = mDevice->px;
01597       p.py = mDevice->py;
01598       p.pa = mDevice->pa;
01599       return(p);
01600     }
01601 
01604     double GetGx() const { return GetVar(mDevice->gx); };
01607     double GetGy() const { return GetVar(mDevice->gy); };
01610     double GetGa() const { return GetVar(mDevice->ga); };
01611 
01613     player_pose2d_t GetGoal() const
01614     {
01615       player_pose2d_t p;
01616       scoped_lock_t lock(mPc->mMutex);
01617       p.px = mDevice->gx;
01618       p.py = mDevice->gy;
01619       p.pa = mDevice->ga;
01620       return(p);
01621     }
01622 
01625     double GetWx() const { return GetVar(mDevice->wx); };
01628     double GetWy() const { return GetVar(mDevice->wy); };
01631     double GetWa() const { return GetVar(mDevice->wa); };
01632 
01634     player_pose2d_t GetCurrentWaypoint() const
01635     {
01636       player_pose2d_t p;
01637       scoped_lock_t lock(mPc->mMutex);
01638       p.px = mDevice->wx;
01639       p.py = mDevice->wy;
01640       p.pa = mDevice->wa;
01641       return(p);
01642     }
01643 
01646     double GetIx(int i) const;
01649     double GetIy(int i) const;
01652     double GetIa(int i) const;
01653 
01655     player_pose2d_t GetWaypoint(uint32_t aIndex) const
01656     {
01657       assert(aIndex < GetWaypointCount());
01658       player_pose2d_t p;
01659       scoped_lock_t lock(mPc->mMutex);
01660       p.px = mDevice->waypoints[aIndex][0];
01661       p.py = mDevice->waypoints[aIndex][1];
01662       p.pa = mDevice->waypoints[aIndex][2];
01663       return(p);
01664     }
01665 
01669     int GetCurrentWaypointId() const
01670       { return GetVar(mDevice->curr_waypoint); };
01671 
01673     uint32_t GetWaypointCount() const
01674       { return GetVar(mDevice->waypoint_count); };
01675 
01680     player_pose2d_t operator [](uint32_t aIndex) const
01681       { return GetWaypoint(aIndex); }
01682 
01683 };
01684 
01688 class PLAYERCC_EXPORT Pointcloud3dProxy : public ClientProxy
01689 {
01690   private:
01691 
01692     void Subscribe(uint32_t aIndex);
01693     void Unsubscribe();
01694 
01695     // libplayerc data structure
01696     playerc_pointcloud3d_t *mDevice;
01697 
01698   public:
01700     Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
01701 
01703     ~Pointcloud3dProxy();
01704 
01706     uint32_t GetCount() const { return GetVar(mDevice->points_count); };
01707 
01709     player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const
01710       { return GetVar(mDevice->points[aIndex]); };
01711 
01714     player_pointcloud3d_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); }
01715 
01716 };
01717 
01718 
01723 class PLAYERCC_EXPORT Position1dProxy : public ClientProxy
01724 {
01725 
01726   private:
01727 
01728     void Subscribe(uint32_t aIndex);
01729     void Unsubscribe();
01730 
01731     // libplayerc data structure
01732     playerc_position1d_t *mDevice;
01733 
01734   public:
01735 
01737     Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0);
01739     ~Position1dProxy();
01740 
01744     void SetSpeed(double aVel);
01745 
01749     void GoTo(double aPos, double aVel);
01750 
01753     void RequestGeom();
01754 
01756     player_pose3d_t GetPose() const
01757     {
01758       player_pose3d_t p;
01759       scoped_lock_t lock(mPc->mMutex);
01760       p.px = mDevice->pose[0];
01761       p.py = mDevice->pose[1];
01762       p.pyaw = mDevice->pose[2];
01763       return(p);
01764     }
01765 
01767     player_bbox3d_t GetSize() const
01768     {
01769       player_bbox3d_t b;
01770       scoped_lock_t lock(mPc->mMutex);
01771       b.sl = mDevice->size[0];
01772       b.sw = mDevice->size[1];
01773       return(b);
01774     }
01775 
01780     void SetMotorEnable(bool enable);
01781 
01784     void SetOdometry(double aPos);
01785 
01787     void ResetOdometry() { SetOdometry(0); };
01788 
01789     // Set PID terms
01790     //void SetSpeedPID(double kp, double ki, double kd);
01791 
01792     // Set PID terms
01793     //void SetPositionPID(double kp, double ki, double kd);
01794 
01795     // Set speed ramping profile
01796     // spd rad/s, acc rad/s/s
01797     //void SetPositionSpeedProfile(double spd, double acc);
01798 
01800     double  GetPos() const { return GetVar(mDevice->pos); };
01801 
01803     double  GetVel() const { return GetVar(mDevice->vel); };
01804 
01806     bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
01807 
01809     uint8_t GetStatus() const { return GetVar(mDevice->status); };
01810 
01812     bool IsLimitMin() const
01813       { return (GetVar(mDevice->status) &
01814                (1 << PLAYER_POSITION1D_STATUS_LIMIT_MIN)) > 0; };
01815 
01817     bool IsLimitCen() const
01818       { return (GetVar(mDevice->status) &
01819                (1 << PLAYER_POSITION1D_STATUS_LIMIT_CEN)) > 0; };
01820 
01822     bool IsLimitMax() const
01823       { return (GetVar(mDevice->status) &
01824                (1 << PLAYER_POSITION1D_STATUS_LIMIT_MAX)) > 0; };
01825 
01827     bool IsOverCurrent() const
01828       { return (GetVar(mDevice->status) &
01829                (1 << PLAYER_POSITION1D_STATUS_OC)) > 0; };
01830 
01832     bool IsTrajComplete() const
01833       { return (GetVar(mDevice->status) &
01834                (1 << PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE)) > 0; };
01835 
01837     bool IsEnabled() const
01838       { return (GetVar(mDevice->status) &
01839                (1 << PLAYER_POSITION1D_STATUS_ENABLED)) > 0; };
01840 
01841 };
01842 
01847 class PLAYERCC_EXPORT Position2dProxy : public ClientProxy
01848 {
01849 
01850   private:
01851 
01852     void Subscribe(uint32_t aIndex);
01853     void Unsubscribe();
01854 
01855     // libplayerc data structure
01856     playerc_position2d_t *mDevice;
01857 
01858   public:
01859 
01861     Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
01863     ~Position2dProxy();
01864 
01868     void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed);
01869 
01872     void SetSpeed(double aXSpeed, double aYawSpeed)
01873         { return SetSpeed(aXSpeed, 0, aYawSpeed);}
01874 
01876     void SetSpeed(player_pose2d_t vel)
01877         { return SetSpeed(vel.px, vel.py, vel.pa);}
01878 
01882     void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead);
01883 
01886     void SetVelHead(double aXSpeed, double aYawHead)
01887         { return SetVelHead(aXSpeed, 0, aYawHead);}
01888 
01889 
01893     void GoTo(player_pose2d_t pos, player_pose2d_t vel);
01894 
01896     void GoTo(player_pose2d_t pos)
01897       { player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
01898 
01901     void GoTo(double aX, double aY, double aYaw)
01902       { player_pose2d_t pos = {aX,aY,aYaw}; player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
01903 
01905     void SetCarlike(double aXSpeed, double aDriveAngle);
01906 
01909     void RequestGeom();
01910 
01912     //  body (fill it in by calling RequestGeom()).
01913     player_pose3d_t GetOffset()
01914     {
01915       player_pose3d_t p;
01916       scoped_lock_t lock(mPc->mMutex);
01917       p.px = mDevice->pose[0];
01918       p.py = mDevice->pose[1];
01919       p.pyaw = mDevice->pose[2];
01920       return(p);
01921     }
01922 
01924     player_bbox3d_t GetSize()
01925     {
01926       player_bbox3d_t b;
01927       scoped_lock_t lock(mPc->mMutex);
01928       b.sl = mDevice->size[0];
01929       b.sw = mDevice->size[1];
01930       return(b);
01931     }
01932 
01937     void SetMotorEnable(bool enable);
01938 
01939     // Select velocity control mode.
01940     //
01941     // For the the p2os_position driver, set @p mode to 0 for direct wheel
01942     // velocity control (default), or 1 for separate translational and
01943     // rotational control.
01944     //
01945     // For the reb_position driver: 0 is direct velocity control, 1 is for
01946     // velocity-based heading PD controller (uses DoDesiredHeading()).
01947     //void SelectVelocityControl(unsigned char mode);
01948 
01950     void ResetOdometry();
01951 
01952     // Select position mode
01953     // Set @p mode for 0 for velocity mode, 1 for position mode.
01954     //void SelectPositionMode(unsigned char mode);
01955 
01958     void SetOdometry(double aX, double aY, double aYaw);
01959 
01960     // Set PID terms
01961     //void SetSpeedPID(double kp, double ki, double kd);
01962 
01963     // Set PID terms
01964     //void SetPositionPID(double kp, double ki, double kd);
01965 
01966     // Set speed ramping profile
01967     // spd rad/s, acc rad/s/s
01968     //void SetPositionSpeedProfile(double spd, double acc);
01969 
01970     //
01971     // void DoStraightLine(double m);
01972 
01973     //
01974     //void DoRotation(double yawspeed);
01975 
01976     //
01977     //void DoDesiredHeading(double yaw, double xspeed, double yawspeed);
01978 
01979     //
01980     //void SetStatus(uint8_t cmd, uint16_t value);
01981 
01982     //
01983     //void PlatformShutdown();
01984 
01986     double  GetXPos() const { return GetVar(mDevice->px); };
01987 
01989     double  GetYPos() const { return GetVar(mDevice->py); };
01990 
01992     double GetYaw() const { return GetVar(mDevice->pa); };
01993 
01995     double  GetXSpeed() const { return GetVar(mDevice->vx); };
01996 
01998     double  GetYSpeed() const { return GetVar(mDevice->vy); };
01999 
02001     double  GetYawSpeed() const { return GetVar(mDevice->va); };
02002 
02004     bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
02005 
02006 };
02007 
02014 class PLAYERCC_EXPORT Position3dProxy : public ClientProxy
02015 {
02016 
02017   private:
02018 
02019     void Subscribe(uint32_t aIndex);
02020     void Unsubscribe();
02021 
02022     // libplayerc data structure
02023     playerc_position3d_t *mDevice;
02024 
02025   public:
02026 
02028     Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
02030     ~Position3dProxy();
02031 
02035     void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed,
02036                   double aRollSpeed, double aPitchSpeed, double aYawSpeed);
02037 
02041     void SetSpeed(double aXSpeed, double aYSpeed,
02042                   double aZSpeed, double aYawSpeed)
02043       { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
02044 
02046     void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
02047       { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
02048 
02051     void SetSpeed(double aXSpeed, double aYawSpeed)
02052       { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
02053 
02055     void SetSpeed(player_pose3d_t vel)
02056       { SetSpeed(vel.px,vel.py,vel.pz,vel.proll,vel.ppitch,vel.pyaw);}
02057 
02061     void GoTo(player_pose3d_t aPos, player_pose3d_t aVel);
02062 
02064     void GoTo(player_pose3d_t aPos)
02065       { player_pose3d_t vel = {0,0,0,0,0,0}; GoTo(aPos, vel); }
02066 
02067 
02070     void GoTo(double aX, double aY, double aZ,
02071               double aRoll, double aPitch, double aYaw)
02072       { player_pose3d_t pos = {aX,aY,aZ,aRoll,aPitch,aYaw}; 
02073         player_pose3d_t vel = {0,0,0,0,0,0}; 
02074         GoTo(pos, vel);
02075       }
02076 
02081     void SetMotorEnable(bool aEnable);
02082 
02085     void SelectVelocityControl(int aMode);
02086 
02088     void ResetOdometry();
02089 
02093     void SetOdometry(double aX, double aY, double aZ,
02094                      double aRoll, double aPitch, double aYaw);
02095 
02098     void RequestGeom();
02099 
02100     // Select position mode
02101     // Set @p mode for 0 for velocity mode, 1 for position mode.
02102     //void SelectPositionMode(unsigned char mode);
02103 
02104     //
02105     //void SetSpeedPID(double kp, double ki, double kd);
02106 
02107     //
02108     //void SetPositionPID(double kp, double ki, double kd);
02109 
02110     // Sets the ramp profile for position based control
02111     // spd rad/s, acc rad/s/s
02112     //void SetPositionSpeedProfile(double spd, double acc);
02113 
02115     double  GetXPos() const { return GetVar(mDevice->pos_x); };
02116 
02118     double  GetYPos() const { return GetVar(mDevice->pos_y); };
02119 
02121     double  GetZPos() const { return GetVar(mDevice->pos_z); };
02122 
02124     double  GetRoll() const { return GetVar(mDevice->pos_roll); };
02125 
02127     double  GetPitch() const { return GetVar(mDevice->pos_pitch); };
02128 
02130     double  GetYaw() const { return GetVar(mDevice->pos_yaw); };
02131 
02133     double  GetXSpeed() const { return GetVar(mDevice->vel_x); };
02134 
02136     double  GetYSpeed() const { return GetVar(mDevice->vel_y); };
02137 
02139     double  GetZSpeed() const { return GetVar(mDevice->vel_z); };
02140 
02142     double  GetRollSpeed() const { return GetVar(mDevice->vel_roll); };
02143 
02145     double  GetPitchSpeed() const { return GetVar(mDevice->vel_pitch); };
02146 
02148     double  GetYawSpeed() const { return GetVar(mDevice->vel_yaw); };
02149 
02151     bool GetStall () const { return GetVar(mDevice->stall) != 0 ? true : false; };
02152 };
02155 class PLAYERCC_EXPORT PowerProxy : public ClientProxy
02156 {
02157   private:
02158 
02159     void Subscribe(uint32_t aIndex);
02160     void Unsubscribe();
02161 
02162     // libplayerc data structure
02163     playerc_power_t *mDevice;
02164 
02165   public:
02167     PowerProxy(PlayerClient *aPc, uint32_t aIndex=0);
02169     ~PowerProxy();
02170 
02172     double GetCharge() const { return GetVar(mDevice->charge); };
02173 
02175     double GetPercent() const {return GetVar(mDevice->percent); };
02176 
02178     double GetJoules() const {return GetVar(mDevice->joules); };
02179 
02181     double GetWatts() const {return GetVar(mDevice->watts); };
02182 
02184     bool GetCharging() const {return GetVar(mDevice->charging) != 0 ? true : false;};
02185 
02186     // Return whether the power data is valid
02187     bool IsValid() const {return GetVar(mDevice->valid) != 0 ? true : false;};
02188 };
02189 
02196 class PLAYERCC_EXPORT PtzProxy : public ClientProxy
02197 {
02198 
02199   private:
02200 
02201     void Subscribe(uint32_t aIndex);
02202     void Unsubscribe();
02203 
02204     // libplayerc data structure
02205     playerc_ptz_t *mDevice;
02206 
02207   public:
02208     // Constructor
02209     PtzProxy(PlayerClient *aPc, uint32_t aIndex=0);
02210     // Destructor
02211     ~PtzProxy();
02212 
02213   public:
02214 
02218     void SetCam(double aPan, double aTilt, double aZoom);
02219 
02221     void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0);
02222 
02225     void SelectControlMode(uint32_t aMode);
02226 
02228     double GetPan() const { return GetVar(mDevice->pan); };
02230     double GetTilt() const { return GetVar(mDevice->tilt); };
02232     double GetZoom() const { return GetVar(mDevice->zoom); };
02233 
02235     int GetStatus();
02236 
02237 
02238 };
02239 
02242 class PLAYERCC_EXPORT RangerProxy : public ClientProxy
02243 {
02244   private:
02245 
02246     void Subscribe(uint32_t aIndex);
02247     void Unsubscribe();
02248 
02249     // libplayerc data structure
02250     playerc_ranger_t *mDevice;
02251 
02252   public:
02254     RangerProxy(PlayerClient *aPc, uint32_t aIndex=0);
02256     ~RangerProxy();
02257 
02259     uint32_t GetElementCount() const { return GetVar(mDevice->element_count); };
02260 
02262     player_pose3d_t GetDevicePose() const { return GetVar(mDevice->device_pose); };
02264     player_bbox3d_t GetDeviceSize() const { return GetVar(mDevice->device_size); };
02265 
02267     player_pose3d_t GetElementPose(uint32_t aIndex) const;
02269     player_bbox3d_t GetElementSize(uint32_t aIndex) const;
02270 
02272     uint32_t GetRangeCount() const { return GetVar(mDevice->ranges_count); };
02274     double GetRange(uint32_t aIndex) const;
02276     double operator[] (uint32_t aIndex) const { return GetRange(aIndex); }
02277 
02279     uint32_t GetIntensityCount() const { return GetVar(mDevice->intensities_count); } ;
02281     double GetIntensity(uint32_t aIndex) const;
02282 
02285     void SetPower(bool aEnable);
02286 
02289     void SetIntensityData(bool aEnable);
02290 
02292     void RequestGeom();
02293 
02298     void Configure(double aMinAngle,
02299                    double aMaxAngle,
02300                    double aAngularRes,
02301                    double aMinRange,
02302                    double aMaxRange,
02303                    double aRangeRes,
02304                    double aFrequency);
02305 
02308     void RequestConfigure();
02309 
02311     double GetMinAngle() const { return GetVar(mDevice->min_angle); };
02312 
02314     double GetMaxAngle() const { return GetVar(mDevice->max_angle); };
02315 
02317     double GetAngularRes() const { return GetVar(mDevice->angular_res); };
02318 
02320     double GetMinRange() const { return GetVar(mDevice->min_range); };
02321 
02323     double GetMaxRange() const { return GetVar(mDevice->max_range); };
02324 
02326     double GetRangeRes() const { return GetVar(mDevice->range_res); };
02327 
02329     double GetFrequency() const { return GetVar(mDevice->frequency); };
02330 };
02331 
02334 class PLAYERCC_EXPORT RFIDProxy : public ClientProxy
02335 {
02336 
02337   private:
02338 
02339     void Subscribe(uint32_t aIndex);
02340     void Unsubscribe();
02341 
02342     // libplayerc data structure
02343     playerc_rfid_t *mDevice;
02344 
02345   public:
02347     RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0);
02349     ~RFIDProxy();
02350 
02352     uint32_t GetTagsCount() const { return GetVar(mDevice->tags_count); };
02354     playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
02355       { return GetVar(mDevice->tags[aIndex]);};
02356 
02361     playerc_rfidtag_t operator [](uint32_t aIndex) const
02362       { return(GetRFIDTag(aIndex)); }
02363 };
02364 
02369 class PLAYERCC_EXPORT SimulationProxy : public ClientProxy
02370 {
02371   private:
02372 
02373     void Subscribe(uint32_t aIndex);
02374     void Unsubscribe();
02375 
02376     // libplayerc data structure
02377     playerc_simulation_t *mDevice;
02378 
02379   public:
02381     SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0);
02383     ~SimulationProxy();
02384 
02387     void SetPose2d(char* identifier, double x, double y, double a);
02388 
02391     void GetPose2d(char* identifier, double& x, double& y, double& a);
02392 
02395     void SetPose3d(char* identifier, double x, double y, double z,
02396                    double roll, double pitch, double yaw);
02397 
02400     void GetPose3d(char* identifier, double& x, double& y, double& z,
02401                    double& roll, double& pitch, double& yaw, double& time);
02402 
02404     void GetProperty(char* identifier, char *name, void *value, size_t value_len );
02405 
02407     void SetProperty(char* identifier, char *name, void *value, size_t value_len );
02408 };
02409 
02410 
02416 class PLAYERCC_EXPORT SonarProxy : public ClientProxy
02417 {
02418   private:
02419 
02420     void Subscribe(uint32_t aIndex);
02421     void Unsubscribe();
02422 
02423     // libplayerc data structure
02424     playerc_sonar_t *mDevice;
02425 
02426   public:
02428     SonarProxy(PlayerClient *aPc, uint32_t aIndex=0);
02430     ~SonarProxy();
02431 
02433     uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
02434 
02436     double GetScan(uint32_t aIndex) const
02437       { if (GetVar(mDevice->scan_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->scan[aIndex]); };
02440     double operator [] (uint32_t aIndex) const { return GetScan(aIndex); }
02441 
02443     uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
02444 
02446     player_pose3d_t GetPose(uint32_t aIndex) const
02447       { return GetVar(mDevice->poses[aIndex]); };
02448 
02449     // Enable/disable the sonars.
02450     // Set @p state to 1 to enable, 0 to disable.
02451     // Note that when sonars are disabled the client will still receive sonar
02452     // data, but the ranges will always be the last value read from the sonars
02453     // before they were disabled.
02454     //void SetEnable(bool aEnable);
02455 
02457     void RequestGeom();
02458 };
02459 
02464 class PLAYERCC_EXPORT SpeechProxy : public ClientProxy
02465 {
02466 
02467   private:
02468 
02469     void Subscribe(uint32_t aIndex);
02470     void Unsubscribe();
02471 
02472     // libplayerc data structure
02473     playerc_speech_t *mDevice;
02474 
02475   public:
02477     SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0);
02479     ~SpeechProxy();
02480 
02483     void Say(std::string aStr);
02484 };
02485 
02489 class PLAYERCC_EXPORT SpeechRecognitionProxy : public ClientProxy
02490 {
02491    void Subscribe(uint32_t aIndex);
02492    void Unsubscribe();
02493 
02495    playerc_speechrecognition_t *mDevice;
02496   public:
02498    SpeechRecognitionProxy(PlayerClient *aPc, uint32_t aIndex=0);
02500    ~SpeechRecognitionProxy();
02502    std::string GetWord(uint32_t aWord) const{
02503      scoped_lock_t lock(mPc->mMutex);
02504      return std::string(mDevice->words[aWord]);
02505    }
02506 
02508    uint32_t GetCount(void) const { return GetVar(mDevice->wordCount); }
02509 
02512    std::string operator [](uint32_t aWord) { return(GetWord(aWord)); }
02513 };
02514 
02518 class PLAYERCC_EXPORT StereoProxy : public ClientProxy
02519 {
02520   private:
02521     void Subscribe(uint32_t aIndex);
02522     void Unsubscribe();
02523 
02525     playerc_stereo_t *mDevice;
02526 
02528     void SaveFrame(const std::string aPrefix, uint32_t aWidth, playerc_camera_t aDevice, uint8_t aIndex);
02529 
02531     void Decompress(playerc_camera_t aDevice);
02532 
02534     std::string mPrefix;
02535 
02537     uint32_t mFrameNo[3];
02538 
02539   public:
02541     StereoProxy(PlayerClient *aPc, uint32_t aIndex=0);
02542 
02544     ~StereoProxy();
02545 
02549     void SaveLeftFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->left_channel, 0); };
02553     void SaveRightFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->right_channel, 1); };
02557     void SaveDisparityFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->disparity, 2); };
02558 
02560     void DecompressLeft(){ return Decompress(mDevice->left_channel); };
02562     void DecompressRight(){ return Decompress(mDevice->right_channel); };
02564     void DecompressDisparity(){ return Decompress(mDevice->disparity); };
02565 
02567     uint32_t GetLeftDepth() const { return GetVar(mDevice->left_channel.bpp); };
02569     uint32_t GetRightDepth() const { return GetVar(mDevice->right_channel.bpp); };
02571     uint32_t GetDisparityDepth() const { return GetVar(mDevice->disparity.bpp); };
02572 
02574     uint32_t GetLeftWidth() const { return GetVar(mDevice->left_channel.width); };
02576     uint32_t GetRightWidth() const { return GetVar(mDevice->right_channel.width); };
02578     uint32_t GetDisparityWidth() const { return GetVar(mDevice->disparity.width); };
02579 
02581     uint32_t GetLeftHeight() const { return GetVar(mDevice->left_channel.height); };
02583     uint32_t GetRightHeight() const { return GetVar(mDevice->right_channel.height); };
02585     uint32_t GetDisparityHeight() const { return GetVar(mDevice->disparity.height); };
02586 
02593     uint32_t GetLeftFormat() const { return GetVar(mDevice->left_channel.format); };
02600     uint32_t GetRightFormat() const { return GetVar(mDevice->right_channel.format); };
02607     uint32_t GetDisparityFormat() const { return GetVar(mDevice->disparity.format); };
02608 
02610     uint32_t GetLeftImageSize() const { return GetVar(mDevice->left_channel.image_count); };
02612     uint32_t GetRightImageSize() const { return GetVar(mDevice->right_channel.image_count); };
02614     uint32_t GetDisparityImageSize() const { return GetVar(mDevice->disparity.image_count); };
02615 
02620     void GetLeftImage(uint8_t* aImage) const
02621       {
02622         return GetVarByRef(mDevice->left_channel.image,
02623                            mDevice->left_channel.image+GetVar(mDevice->left_channel.image_count),
02624                            aImage);
02625       };
02630     void GetRightImage(uint8_t* aImage) const
02631       {
02632         return GetVarByRef(mDevice->right_channel.image,
02633                            mDevice->right_channel.image+GetVar(mDevice->right_channel.image_count),
02634                            aImage);
02635       };
02640     void GetDisparityImage(uint8_t* aImage) const
02641       {
02642         return GetVarByRef(mDevice->disparity.image,
02643                            mDevice->disparity.image+GetVar(mDevice->disparity.image_count),
02644                            aImage);
02645       };
02646 
02651     uint32_t GetLeftCompression() const { return GetVar(mDevice->left_channel.compression); };
02656     uint32_t GetRightCompression() const { return GetVar(mDevice->right_channel.compression); };
02661     uint32_t GetDisparityCompression() const { return GetVar(mDevice->disparity.compression); };
02662 
02664     uint32_t GetCount() const { return GetVar(mDevice->points_count); };
02665 
02667     player_pointcloud3d_stereo_element_t GetPoint(uint32_t aIndex) const
02668       { return GetVar(mDevice->points[aIndex]); };
02669 
02672     player_pointcloud3d_stereo_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); }
02673 
02674 };
02675 
02679 class PLAYERCC_EXPORT VectorMapProxy : public ClientProxy
02680 {
02681 
02682   private:
02683 
02684     // Subscribe
02685     void Subscribe(uint32_t aIndex);
02686     // Unsubscribe
02687     void Unsubscribe();
02688 
02689     // libplayerc data structure
02690     playerc_vectormap_t *mDevice;
02691 
02692     bool map_info_cached;
02693   public:
02695     VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0);
02697     ~VectorMapProxy();
02698 
02700     void GetMapInfo();
02701 
02703     void GetLayerData(unsigned layer_index);
02704 
02706     int GetLayerCount() const;
02707 
02709     std::vector<std::string> GetLayerNames() const;
02710 
02712     int GetFeatureCount(unsigned layer_index) const;
02713 
02715     const uint8_t * GetFeatureData(unsigned layer_index, unsigned feature_index) const;
02716 
02718     size_t GetFeatureDataCount(unsigned layer_index, unsigned feature_index) const;
02719 };
02720 
02723 class PLAYERCC_EXPORT WiFiProxy: public ClientProxy
02724 {
02725 
02726   private:
02727 
02728     void Subscribe(uint32_t aIndex);
02729     void Unsubscribe();
02730 
02731     // libplayerc data structure
02732     playerc_wifi_t *mDevice;
02733 
02734   public:
02736     WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0);
02738     ~WiFiProxy();
02739 
02741     const playerc_wifi_link_t *GetLink(int aLink);
02742 
02744     int GetLinkCount() const { return mDevice->link_count; };
02746     char* GetOwnIP() const { return mDevice->ip; };
02748     char* GetLinkIP(int index)  const { return (char*) mDevice->links[index].ip; };
02750     char* GetLinkMAC(int index)  const { return (char*) mDevice->links[index].mac; };
02752     char* GetLinkESSID(int index)  const { return (char*)mDevice->links[index].essid; };
02754     double GetLinkFreq(int index)  const {return mDevice->links[index].freq;};
02756     int GetLinkMode(int index)  const { return mDevice->links[index].mode; };
02758     int GetLinkEncrypt(int index)  const {return mDevice->links[index].encrypt; };
02760     int GetLinkQuality(int index)  const { return mDevice->links[index].qual; };
02762     int GetLinkLevel(int index)  const {return mDevice->links[index].level; };
02764     int GetLinkNoise(int index)  const {return mDevice->links[index].noise; }   ;
02765 
02766 };
02767 
02770 class PLAYERCC_EXPORT WSNProxy : public ClientProxy
02771 {
02772 
02773   private:
02774 
02775     void Subscribe(uint32_t aIndex);
02776     void Unsubscribe();
02777 
02778     // libplayerc data structure
02779     playerc_wsn_t *mDevice;
02780 
02781   public:
02783     WSNProxy(PlayerClient *aPc, uint32_t aIndex=0);
02785     ~WSNProxy();
02786 
02788     uint32_t GetNodeType    () const { return GetVar(mDevice->node_type);      };
02790     uint32_t GetNodeID      () const { return GetVar(mDevice->node_id);        };
02792     uint32_t GetNodeParentID() const { return GetVar(mDevice->node_parent_id); };
02793 
02795     player_wsn_node_data_t
02796        GetNodeDataPacket() const { return GetVar(mDevice->data_packet);    };
02797 
02799     void SetDevState(int nodeID, int groupID, int devNr, int value);
02801     void Power(int nodeID, int groupID, int value);
02803     void DataType(int value);
02805     void DataFreq(int nodeID, int groupID, float frequency);
02806 };
02807 
02809 }
02810 
02811 namespace std
02812 {
02813   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_point_2d_t& c);
02814   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose2d_t& c);
02815   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose3d_t& c);
02816   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox2d_t& c);
02817   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox3d_t& c);
02818   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_segment_t& c);
02819   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_extent2d_t& c);
02820   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const playerc_device_info_t& c);
02821 
02822   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ClientProxy& c);
02823   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ActArrayProxy& c);
02824   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AioProxy& c);
02825   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AudioProxy& a);
02826   //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlinkenLightProxy& c);
02827   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlobfinderProxy& c);
02828   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BumperProxy& c);
02829   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::CameraProxy& c);
02830   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::DioProxy& c);
02831   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::FiducialProxy& c);
02832   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GpsProxy& c);
02833   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GripperProxy& c);
02834   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ImuProxy& c);
02835   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::IrProxy& c);
02836   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LaserProxy& c);
02837   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LimbProxy& c);
02838   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LinuxjoystickProxy& c);
02839   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LocalizeProxy& c);
02840   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LogProxy& c);
02841   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::MapProxy& c);
02842   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::OpaqueProxy& c);
02843   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PlannerProxy& c);
02844   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position1dProxy& c);
02845   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position2dProxy& c);
02846   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position3dProxy& c);
02847   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PowerProxy& c);
02848   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PtzProxy& c);
02849   PLAYERCC_EXPORT std::ostream& operator << (std::ostream &os, const PlayerCc::RangerProxy &c);
02850   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SimulationProxy& c);
02851   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SonarProxy& c);
02852   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechProxy& c);
02853   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechRecognitionProxy& c);
02854   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::StereoProxy& c);
02855   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::VectorMapProxy& c);
02856   //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WafeformProxy& c);
02857   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WiFiProxy& c);
02858   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::RFIDProxy& c);
02859   PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WSNProxy& c);
02860 }
02861 
02862 #endif
02863