00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032 #ifndef PLAYERCC_H
00033 #define PLAYERCC_H
00034
00035 #include <cmath>
00036 #include <string>
00037 #include <list>
00038
00039 #include "libplayerc/playerc.h"
00040 #include "libplayerc++/playerc++config.h"
00041 #include "libplayerc++/playerclient.h"
00042 #include "libplayerc++/playererror.h"
00043
00044
00045 #ifdef HAVE_BOOST_SIGNALS
00046 #include <boost/signal.hpp>
00047 #include <boost/bind.hpp>
00048 #endif
00049
00050 #ifdef HAVE_BOOST_THREAD
00051 #include <boost/thread/mutex.hpp>
00052 #include <boost/thread/thread.hpp>
00053 #include <boost/thread/xtime.hpp>
00054 #endif
00055
00056 namespace PlayerCc
00057 {
00076
00077
00078
00080 inline double rtod(double r)
00081 {
00082 return r * 180.0 / M_PI;
00083 }
00084
00086 inline double dtor(double r)
00087 {
00088 return r * M_PI / 180.0;
00089 }
00090
00092 inline double normalize(double z)
00093 {
00094 return atan2(sin(z), cos(z));
00095 }
00096
00098 template<typename T>
00099 inline T min(T a, T b)
00100 {
00101 if (a < b)
00102 return a;
00103 else
00104 return b;
00105 }
00106
00108 template<typename T>
00109 inline T max(T a, T b)
00110 {
00111 if (a > b)
00112 return a;
00113 else
00114 return b;
00115 }
00116
00118 template<typename T>
00119 inline T limit(T a, T min, T max)
00120 {
00121 if (a < min)
00122 return min;
00123 else if (a > max)
00124 return max;
00125 else
00126 return a;
00127 }
00128
00153 class ClientProxy
00154 {
00155 friend class PlayerClient;
00156
00157 public:
00158
00159 #ifdef HAVE_BOOST_SIGNALS
00162 typedef boost::signals::connection connection_t;
00163
00164
00165 typedef boost::mutex::scoped_lock scoped_lock_t;
00166
00167
00168 typedef boost::signal<void (void)> read_signal_t;
00169 #else
00170
00171 typedef int connection_t;
00172
00173 typedef boost::mutex::scoped_lock scoped_lock_t;
00174 typedef int read_signal_t;
00175 #endif
00176
00177 protected:
00178
00179
00180
00181
00182
00183 ClientProxy(PlayerClient* aPc, uint aIndex);
00184
00185
00186 virtual ~ClientProxy();
00187
00188
00189
00190
00191
00192
00193
00194 virtual void Subscribe(uint aIndex) {};
00195
00196
00197
00198 virtual void Unsubscribe() {};
00199
00200
00201 PlayerClient* mPc;
00202
00203
00204 playerc_client_t* mClient;
00205
00206
00207 playerc_device_t *mInfo;
00208
00209
00210 bool mFresh;
00211
00212
00213
00214
00215 template<typename T>
00216 T GetVar(const T &aV) const
00217 {
00218 scoped_lock_t lock(mPc->mMutex);
00219 T v = aV;
00220 return v;
00221 }
00222
00223
00224
00225
00226
00227
00228
00229 template<typename T>
00230 void GetVarByRef(const T aBegin, const T aEnd, T aDest) const
00231 {
00232 scoped_lock_t lock(mPc->mMutex);
00233 std::copy(aBegin, aEnd, aDest);
00234 }
00235
00236 private:
00237
00238
00239 double mLastTime;
00240
00241
00242
00243
00244
00245
00246
00247
00248
00249
00250
00251
00252
00253
00254
00255
00256
00257 read_signal_t mReadSignal;
00258
00259
00260 void ReadSignal();
00261
00262 public:
00263
00265 bool IsValid() const { return 0!=GetVar(mInfo->datatime); };
00266
00270 bool IsFresh() const { return GetVar(mFresh); };
00271
00273 void NotFresh();
00274
00277 std::string GetDriverName() const { return mInfo->drivername; };
00278
00280 double GetDataTime() const { return GetVar(mInfo->datatime); };
00281
00283 double GetElapsedTime() const
00284 { return GetVar(mInfo->datatime) - GetVar(mInfo->lasttime); };
00285
00287 uint GetIndex() const { return GetVar(mInfo->addr.index); };
00288
00290 uint GetInterface() const { return GetVar(mInfo->addr.interf); };
00291
00293 std::string GetInterfaceStr() const
00294 { return playerc_lookup_name(GetVar(mInfo->addr.interf)); };
00295
00298 template<typename T>
00299 connection_t ConnectReadSignal(T aSubscriber)
00300 {
00301 #ifdef HAVE_BOOST_SIGNALS
00302 scoped_lock_t lock(mPc->mMutex);
00303 return mReadSignal.connect(aSubscriber);
00304 #else
00305 return -1;
00306 #endif
00307 }
00308
00310 void DisconnectReadSignal(connection_t aSubscriber)
00311 {
00312 #ifdef HAVE_BOOST_SIGNALS
00313 scoped_lock_t lock(mPc->mMutex);
00314 aSubscriber.disconnect();
00315 #endif
00316 }
00317
00318 };
00319
00322 #if 0
00323
00328 class SomethingProxy : public ClientProxy
00329 {
00330
00331 private:
00332
00333
00334 void Subscribe(uint aIndex);
00335
00336 void Unsubscribe();
00337
00338
00339 playerc_something_t *mDevice;
00340
00341 public:
00342
00343 SomethingProxy(PlayerClient *aPc, uint aIndex=0);
00344
00345 ~SomethingProxy();
00346
00347 };
00348
00349 #endif
00350
00360
00361
00362
00363
00364
00365
00370 class ActArrayProxy : public ClientProxy
00371 {
00372 private:
00373
00374 void Subscribe(uint aIndex);
00375 void Unsubscribe();
00376
00377
00378 playerc_actarray_t *mDevice;
00379
00380 public:
00381
00383 ActArrayProxy(PlayerClient *aPc, uint aIndex=0);
00385 ~ActArrayProxy();
00386
00389 void RequestGeometry(void);
00390
00392 void SetPowerConfig(bool aVal);
00394 void SetBrakesConfig(bool aVal);
00396 void SetSpeedConfig(uint aJoint, float aSpeed);
00397
00399 void MoveTo(uint aJoint, float aPos);
00401 void MoveAtSpeed(uint aJoint, float aSpeed);
00403 void MoveHome(int aJoint);
00404
00406 uint GetCount(void) const { return GetVar(mDevice->actuators_count); }
00408 player_actarray_actuator_t GetActuatorData(uint aJoint) const;
00410 player_actarray_actuatorgeom_t GetActuatorGeom(uint aJoint) const;
00411
00416 player_actarray_actuator_t operator [](uint aJoint)
00417 { return(GetActuatorData(aJoint)); }
00418 };
00419
00423 class AioProxy : public ClientProxy
00424 {
00425 private:
00426
00427 void Subscribe(uint aIndex);
00428 void Unsubscribe();
00429
00430
00431 playerc_aio_t *mDevice;
00432
00433 public:
00434
00435 AioProxy (PlayerClient *aPc, uint aIndex=0);
00436 ~AioProxy();
00437
00439 uint GetCount() const { return(GetVar(mDevice->voltages_count)); };
00440
00442 double GetVoltage(uint aIndex) const
00443 { return(GetVar(mDevice->voltages[aIndex])); };
00444
00446 void SetVoltage(uint aIndex, double aVoltage);
00447
00452 bool operator [](uint aIndex) const
00453 { return GetVoltage(aIndex); }
00454
00455 };
00456
00457 #if 0 // Not in libplayerc
00458
00462 class AudioProxy : public ClientProxy
00463 {
00464
00465 private:
00466
00467 void Subscribe(uint aIndex);
00468 void Unsubscribe();
00469
00470
00471 playerc_audio_t *mDevice;
00472
00473 public:
00474
00475 AudioProxy(PlayerClient *aPc, uint aIndex=0)
00476 ~AudioProxy();
00477
00478 uint GetCount() const { return(GetVar(mDevice->count)); };
00479
00480 double GetFrequency(uint aIndex) const
00481 { return(GetVar(mDevice->frequency[aIndex])); };
00482 double GetAmplitude(uint aIndex) const
00483 { return(GetVar(mDevice->amplitude[aIndex])); };
00484
00485
00486 void PlayTone(uint aFreq, uint aAmp, uint aDur);
00487 };
00488
00494 class AudioDspProxy : public ClientProxy
00495 {
00496 private:
00497
00498 void Subscribe(uint aIndex);
00499 void Unsubscribe();
00500
00501
00502 playerc_audiodsp_t *mDevice;
00503
00504 public:
00505 AudioDspProxy(PlayerClient *aPc, uint aIndex=0);
00506 ~AudioDspProxy
00507
00509 uint SetFormat(int aFormat);
00510
00512 uint SetRate(uint aRate);
00513
00514 uint GetCount() const { return(GetVar(mDevice->count)); };
00515
00516 double GetFrequency(uint aIndex) const
00517 { return(GetVar(mDevice->frequency[aIndex])); };
00518 double GetAmplitude(uint aIndex) const
00519 { return(GetVar(mDevice->amplitude[aIndex])); };
00520
00521 void Configure(uint aChan, uint aRate, int16_t aFormat=0xFFFFFFFF );
00522
00523 void RequestConfigure();
00524
00526 void PlayTone(uint aFreq, uint aAmp, uint aDur);
00527 void PlayChirp(uint aFreq, uint aAmp, uint aDur,
00528 const uint8_t aBitString, uint aBitStringLen);
00529 void Replay();
00530
00532 void Print ();
00533 };
00534
00538 class AudioMixerProxy : public ClientProxy
00539 {
00540 private:
00541
00542 void Subscribe(uint aIndex);
00543 void Unsubscribe();
00544
00545
00546 playerc_audiodsp_t *mDevice;
00547
00548 public:
00549
00550 AudioMixerProxy (PlayerClient *aPc, uint aIndex=0);
00551
00552 void GetConfigure();
00553
00554 void SetMaster(uint aLeft, uint aRight);
00555 void SetPCM(uint aLeft, uint aRight);
00556 void SetLine(uint aLeft, uint aRight);
00557 void SetMic(uint aLeft, uint aRight);
00558 void SetIGain(uint aGain);
00559 void SetOGain(uint aGain);
00560
00561 };
00562
00567 class BlinkenLightProxy : public ClientProxy
00568 {
00569 private:
00570
00571 void Subscribe(uint aIndex);
00572 void Unsubscribe();
00573
00574
00575 playerc_blinkenlight_t *mDevice;
00576
00577 public:
00581 BlinkenLightProxy(PlayerClient *aPc, uint aIndex=0);
00582 ~BlinkenLightProxy();
00583
00584
00585 bool GetEnable();
00586
00591 void SetPeriod(double aPeriod);
00592
00597 void SetEnable(bool aSet);
00598 };
00599
00600 #endif
00601
00608 class BlobfinderProxy : public ClientProxy
00609 {
00610 private:
00611
00612 void Subscribe(uint aIndex);
00613 void Unsubscribe();
00614
00615
00616 playerc_blobfinder_t *mDevice;
00617
00618 public:
00620 BlobfinderProxy(PlayerClient *aPc, uint aIndex=0);
00622 ~BlobfinderProxy();
00623
00625 uint GetCount() const { return GetVar(mDevice->blobs_count); };
00627 playerc_blobfinder_blob_t GetBlob(uint aIndex) const
00628 { return GetVar(mDevice->blobs[aIndex]);};
00629
00631 uint GetWidth() const { return GetVar(mDevice->width); };
00633 uint GetHeight() const { return GetVar(mDevice->height); };
00634
00639 playerc_blobfinder_blob_t operator [](uint aIndex) const
00640 { return(GetBlob(aIndex)); }
00641
00642
00644
00645
00646
00647
00648
00649
00650
00651
00652
00653 };
00654
00659 class BumperProxy : public ClientProxy
00660 {
00661
00662 private:
00663
00664 void Subscribe(uint aIndex);
00665 void Unsubscribe();
00666
00667
00668 playerc_bumper_t *mDevice;
00669
00670 public:
00671
00672 BumperProxy(PlayerClient *aPc, uint aIndex=0);
00673 ~BumperProxy();
00674
00675 uint GetCount() const { return GetVar(mDevice->bumper_count); };
00676
00678 uint IsBumped(uint aIndex) const
00679 { return GetVar(mDevice->bumpers[aIndex]); };
00680
00682 bool IsAnyBumped();
00683
00685 void RequestBumperConfig();
00686
00688 uint GetPoseCount() const { return GetVar(mDevice->pose_count); };
00689
00691 player_bumper_define_t GetPose(uint aIndex) const
00692 { return GetVar(mDevice->poses[aIndex]); };
00693
00698 bool operator [](uint aIndex) const
00699 { return IsBumped(aIndex); }
00700
00701 };
00702
00706 class CameraProxy : public ClientProxy
00707 {
00708
00709 private:
00710
00711 virtual void Subscribe(uint aIndex);
00712 virtual void Unsubscribe();
00713
00714
00715 playerc_camera_t *mDevice;
00716
00717 std::string mPrefix;
00718 int mFrameNo;
00719
00720 public:
00721
00723 CameraProxy (PlayerClient *aPc, uint aIndex=0);
00724
00725 virtual ~CameraProxy();
00726
00728 void SaveFrame(const std::string aPrefix, uint aWidth=4);
00729
00731 void Decompress();
00732
00734 uint GetDepth() const { return GetVar(mDevice->bpp); };
00735
00737 uint GetWidth() const { return GetVar(mDevice->width); };
00738
00740 uint GetHeight() const { return GetVar(mDevice->height); };
00741
00743 uint GetFormat() const { return GetVar(mDevice->format); };
00744
00746 uint GetImageSize() const { return GetVar(mDevice->image_count); };
00747
00749 void GetImage(uint8_t* aImage) const
00750 {
00751 return GetVarByRef(mDevice->image,
00752 mDevice->image+GetVar(mDevice->image_count),
00753 aImage);
00754 };
00755
00757 uint GetCompression() const { return GetVar(mDevice->compression); };
00758
00759 };
00760
00761
00766 class DioProxy : public ClientProxy
00767 {
00768 private:
00769
00770 void Subscribe(uint aIndex);
00771 void Unsubscribe();
00772
00773
00774 playerc_dio_t *mDevice;
00775
00776 public:
00778 DioProxy(PlayerClient *aPc, uint aIndex=0);
00780 ~DioProxy();
00781
00783 uint GetCount() const { return GetVar(mDevice->count); };
00784
00786 uint32_t GetDigin() const { return GetVar(mDevice->digin); };
00787
00789 void SetOutput(uint aCount, uint32_t aDigout);
00790 };
00791
00792 #if 0 // not libplayerc yet
00793
00794
00799 class EnergyProxy : public ClientProxy
00800 {
00801 private:
00802
00803 void Subscribe(uint aIndex);
00804 void Unsubscribe();
00805
00806
00807 playerc_energy_t *mDevice;
00808
00809 public:
00810
00811 EnergyProxy(PlayerClient *aPc, uint aIndex=0);
00812 ~EnergyProxy();
00813
00815 uint GetJoules() const { return GetVar(mDevice->joules); };
00817 uint GetWatts() const { return GetVar(mDevice->watts); };
00819 bool GetCharging() const { return GetVar(mDevice->charging); };
00820 };
00821
00822 #endif
00823
00829 class FiducialProxy : public ClientProxy
00830 {
00831 private:
00832 void Subscribe(uint aIndex);
00833 void Unsubscribe();
00834
00835
00836 playerc_fiducial_t *mDevice;
00837
00838 public:
00840 FiducialProxy(PlayerClient *aPc, uint aIndex=0);
00842 ~FiducialProxy();
00843
00845 uint GetCount() const { return GetVar(mDevice->fiducials_count); };
00846
00848 player_fiducial_item_t GetFiducialItem(uint aIndex) const
00849 { return GetVar(mDevice->fiducials[aIndex]);};
00850
00852 player_pose_t GetSensorPose() const
00853 { return GetVar(mDevice->fiducial_geom.pose);};
00854
00856 player_bbox_t GetSensorSize() const
00857 { return GetVar(mDevice->fiducial_geom.size);};
00858
00860 player_bbox_t GetFiducialSize() const
00861 { return GetVar(mDevice->fiducial_geom.fiducial_size);};
00862
00864 void RequestGeometry();
00865
00870 player_fiducial_item_t operator [](uint aIndex) const
00871 { return GetFiducialItem(aIndex); }
00872 };
00873
00877 class GpsProxy : public ClientProxy
00878 {
00879
00880 private:
00881
00882 void Subscribe(uint aIndex);
00883 void Unsubscribe();
00884
00885
00886 playerc_gps_t *mDevice;
00887
00888 public:
00889
00890
00891 GpsProxy(PlayerClient *aPc, uint aIndex=0);
00892
00893 ~GpsProxy();
00894
00896 double GetLatitude() const { return GetVar(mDevice->lat); };
00897 double GetLongitude() const { return GetVar(mDevice->lon); };
00898
00900 double GetAltitude() const { return GetVar(mDevice->alt); };
00901
00903 uint GetSatellites() const { return GetVar(mDevice->sat_count); };
00904
00906 uint GetQuality() const { return GetVar(mDevice->quality); };
00907
00909 double GetHdop() const { return GetVar(mDevice->hdop); };
00910
00912 double GetVdop() const { return GetVar(mDevice->vdop); };
00913
00915 double GetUtmEasting() const { return GetVar(mDevice->utm_e); };
00916 double GetUtmNorthing() const { return GetVar(mDevice->utm_n); };
00917
00919 double GetTime() const { return GetVar(mDevice->utc_time); };
00920
00922 double GetErrHorizontal() const { return GetVar(mDevice->err_horz); };
00923 double GetErrVertical() const { return GetVar(mDevice->err_vert); };
00924 };
00925
00933 class Graphics2dProxy : public ClientProxy
00934 {
00935
00936 private:
00937
00938
00939 void Subscribe(uint aIndex);
00940
00941 void Unsubscribe();
00942
00943
00944 playerc_graphics2d_t *mDevice;
00945
00946 public:
00947
00948 Graphics2dProxy(PlayerClient *aPc, uint aIndex=0);
00949
00950 ~Graphics2dProxy();
00951
00953 void Color( player_color_t col );
00954
00956 void Color( uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha );
00957
00959 void Clear( void );
00960
00962 void DrawPoints( player_point_2d_t pts[], int count );
00963
00965 void DrawPolygon( player_point_2d_t pts[], int count, bool filled, player_color_t fill_color );
00966
00968 void DrawPolyline( player_point_2d_t pts[], int count );
00969 };
00970
00976 class GripperProxy : public ClientProxy
00977 {
00978
00979 private:
00980
00981 void Subscribe(uint aIndex);
00982 void Unsubscribe();
00983
00984
00985 playerc_gripper_t *mDevice;
00986
00987 public:
00988
00990 GripperProxy(PlayerClient *aPc, uint aIndex=0);
00992 ~GripperProxy();
00993
00995 uint GetState() const { return GetVar(mDevice->state); };
00997 uint GetBeams() const { return GetVar(mDevice->beams); };
00999 uint GetOuterBreakBeam() const
01000 { return GetVar(mDevice->outer_break_beam); };
01002 uint GetInnerBreakBeam() const
01003 { return GetVar(mDevice->inner_break_beam); };
01005 uint GetPaddlesOpen() const
01006 { return GetVar(mDevice->paddles_open); };
01008 uint GetPaddlesClosed() const
01009 { return GetVar(mDevice->paddles_closed); };
01011 uint GetPaddlesMoving() const
01012 { return GetVar(mDevice->paddles_moving); };
01014 uint GetGripperError() const
01015 { return GetVar(mDevice->gripper_error); };
01017 uint GetLiftUp() const { return GetVar(mDevice->lift_up); };
01019 uint GetLiftDown() const { return GetVar(mDevice->lift_down); };
01021 uint GetLiftMoving() const { return GetVar(mDevice->lift_moving); };
01023 uint GetLiftError() const { return GetVar(mDevice->lift_error); };
01024
01027 void SetGrip(uint8_t aCmd, uint8_t aArg=0);
01028 };
01029
01030
01031
01036 class IrProxy : public ClientProxy
01037 {
01038
01039 private:
01040
01041 void Subscribe(uint aIndex);
01042 void Unsubscribe();
01043
01044
01045 playerc_ir_t *mDevice;
01046
01047 public:
01048
01050 IrProxy(PlayerClient *aPc, uint aIndex=0);
01052 ~IrProxy();
01053
01055 uint GetCount() const { return GetVar(mDevice->ranges.ranges_count); };
01057 double GetRange(uint aIndex) const
01058 { return GetVar(mDevice->ranges.ranges[aIndex]); };
01060 double GetVoltage(uint aIndex) const
01061 { return GetVar(mDevice->ranges.voltages[aIndex]); };
01063 uint GetPoseCount() const { return GetVar(mDevice->poses.poses_count); };
01065 player_pose_t GetPose(uint aIndex) const
01066 {return GetVar(mDevice->poses.poses[aIndex]);};
01067
01069 void RequestGeom();
01070
01075 double operator [](uint aIndex) const
01076 { return GetRange(aIndex); }
01077
01078 };
01079
01085 class LaserProxy : public ClientProxy
01086 {
01087 private:
01088
01089 void Subscribe(uint aIndex);
01090 void Unsubscribe();
01091
01092
01093 playerc_laser_t *mDevice;
01094
01095 double aMinLeft;
01096 double aMinRight;
01097
01098
01099 double min_angle, max_angle, scan_res, range_res;
01100 bool intensity;
01101
01102 public:
01103
01105 LaserProxy(PlayerClient *aPc, uint aIndex=0);
01107 ~LaserProxy();
01108
01110 uint GetCount() const { return GetVar(mDevice->scan_count); };
01111
01113 double GetScanRes() const { return GetVar(mDevice->scan_res); };
01114
01116 double GetRangeRes() const { return GetVar(mDevice->range_res); };
01117
01118
01120 double GetMaxAngle() const { return GetVar(mDevice->scan_start); };
01122 double GetMinAngle() const { return GetVar(mDevice->scan_start) + GetVar(mDevice->scan_count)*GetVar(mDevice->scan_res); };
01123
01124
01125
01126
01128
01129
01130
01132 player_point_2d_t GetPoint(uint aIndex) const
01133 { return GetVar(mDevice->point[aIndex]); };
01134
01135
01137 double GetRange(uint aIndex) const
01138 { return GetVar(mDevice->ranges[aIndex]); };
01139
01141 double GetIntensity(uint aIndex) const
01142 { return GetVar(mDevice->intensity[aIndex]); };
01143
01151 void Configure(double aMinAngle,
01152 double aMaxAngle,
01153 uint aScanRes,
01154 uint aRangeRes,
01155 bool aIntensity);
01156
01159 void RequestConfigure();
01160
01163 void RequestGeom();
01164
01166 player_pose_t GetPose()
01167 {
01168 player_pose_t p;
01169 scoped_lock_t lock(mPc->mMutex);
01170
01171 p.px = mDevice->pose[0];
01172 p.py = mDevice->pose[1];
01173 p.pa = mDevice->pose[2];
01174 return(p);
01175 }
01176
01178 player_bbox_t GetSize()
01179 {
01180 player_bbox_t b;
01181 scoped_lock_t lock(mPc->mMutex);
01182
01183 b.sl = mDevice->size[0];
01184 b.sw = mDevice->size[1];
01185 return(b);
01186 }
01187
01189 double MinLeft () { return aMinLeft; }
01191 double MinRight () { return aMinRight; }
01192
01198 double operator [] (uint index) const
01199 { return GetRange(index);}
01200
01201 };
01202
01207 class LimbProxy : public ClientProxy
01208 {
01209 private:
01210
01211 void Subscribe(uint aIndex);
01212 void Unsubscribe();
01213
01214
01215 playerc_limb_t *mDevice;
01216
01217 public:
01218
01219 LimbProxy(PlayerClient *aPc, uint aIndex=0);
01220 ~LimbProxy();
01221
01224 void RequestGeometry(void);
01225
01227 void SetPowerConfig(bool aVal);
01229 void SetBrakesConfig(bool aVal);
01231 void SetSpeedConfig(float aSpeed);
01232
01234 void MoveHome(void);
01236 void Stop(void);
01238 void SetPose(float aPX, float aPY, float aPZ,
01239 float aAX, float aAY, float aAZ,
01240 float aOX, float aOY, float aOZ);
01242 void SetPosition(float aX, float aY, float aZ);
01245 void VectorMove(float aX, float aY, float aZ, float aLength);
01246
01248 player_limb_data_t GetData(void) const;
01250 player_limb_geom_req_t GetGeom(void) const;
01251 };
01252
01258 class LocalizeProxy : public ClientProxy
01259 {
01260
01261 private:
01262
01263 void Subscribe(uint aIndex);
01264 void Unsubscribe();
01265
01266
01267 playerc_localize_t *mDevice;
01268
01269 public:
01270
01272 LocalizeProxy(PlayerClient *aPc, uint aIndex=0);
01274 ~LocalizeProxy();
01275
01277
01278 uint GetMapSizeX() const { return GetVar(mDevice->map_size_x); };
01279 uint GetMapSizeY() const { return GetVar(mDevice->map_size_y); };
01280
01281
01282 uint GetMapTileX() const { return GetVar(mDevice->map_tile_x); };
01283 uint GetMapTileY() const { return GetVar(mDevice->map_tile_y); };
01284
01286 double GetMapScale() const { return GetVar(mDevice->map_scale); };
01287
01288
01289
01290
01291
01292
01293
01294
01295
01296
01298 uint GetPendingCount() const { return GetVar(mDevice->pending_count); };
01299
01301 uint GetHypothCount() const { return GetVar(mDevice->hypoth_count); };
01302
01304 player_localize_hypoth_t GetHypoth(uint aIndex) const
01305 { return GetVar(mDevice->hypoths[aIndex]); };
01306
01308 void SetPose(double pose[3], double cov[3]);
01309
01311 uint GetNumHypoths() const { return GetVar(mDevice->hypoth_count); };
01312
01315 uint GetNumParticles() const { return GetVar(mDevice->num_particles); };
01316 };
01317
01321 class LogProxy : public ClientProxy
01322 {
01323 private:
01324
01325 void Subscribe(uint aIndex);
01326 void Unsubscribe();
01327
01328
01329 playerc_log_t *mDevice;
01330
01331 public:
01333 LogProxy(PlayerClient *aPc, uint aIndex=0);
01334
01336 ~LogProxy();
01337
01340 int GetType() const { return GetVar(mDevice->type); };
01341
01343 int GetState() const { return GetVar(mDevice->state); };
01344
01346 void SetWriteState(int aState);
01347
01349 void SetReadState(int aState);
01350
01352 void Rewind();
01353
01355 void SetFilename(const std::string aFilename);
01356 };
01357
01361 class MapProxy : public ClientProxy
01362 {
01363 private:
01364
01365 void Subscribe(uint aIndex);
01366 void Unsubscribe();
01367
01368
01369 playerc_map_t *mDevice;
01370
01371 public:
01373 MapProxy(PlayerClient *aPc, uint aIndex=0);
01374
01376 ~MapProxy();
01377
01379 void RequestMap();
01380
01382 int GetCellIndex(int x, int y) const
01383 { return y*GetWidth() + x; };
01384
01386 unsigned char GetCell(int x, int y ) const
01387 { return GetVar(mDevice->cells[GetCellIndex(x,y)]); };
01388
01390 double GetResolution() const { return GetVar(mDevice->resolution); };
01391
01394 uint GetWidth() const { return GetVar(mDevice->width); };
01397 uint GetHeight() const { return GetVar(mDevice->height); };
01398
01399 double GetOriginX() const { return GetVar(mDevice->origin[0]); };
01400 double GetOriginY() const { return GetVar(mDevice->origin[1]); };
01401
01403 void GetMap(int8_t* aMap) const
01404 {
01405 return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->cells),
01406 reinterpret_cast<int8_t*>(mDevice->cells+GetWidth()*GetHeight()),
01407 aMap);
01408 };
01409 };
01410
01411 #if 0
01412
01419 class McomProxy : public ClientProxy
01420 {
01421 private:
01422
01423 void Subscribe(uint aIndex);
01424 void Unsubscribe();
01425
01426
01427 playerc_mcom_t *mDevice;
01428
01431 player_mcom_data_t data;
01432 int type;
01433 char channel[MCOM_CHANNEL_LEN];
01434
01435 public:
01436 McomProxy(PlayerClient* pc, unsigned short index,
01437 unsigned char access = 'c') :
01438 ClientProxy(pc,PLAYER_MCOM_CODE,index,access){}
01439
01444 int Pop(int type, char channel[MCOM_CHANNEL_LEN]);
01445
01452 int Read(int type, char channel[MCOM_CHANNEL_LEN]);
01453
01455 int Push(int type, char channel[MCOM_CHANNEL_LEN], char dat[MCOM_DATA_LEN]);
01456
01458 int Clear(int type, char channel[MCOM_CHANNEL_LEN]);
01459
01462 int SetCapacity(int type, char channel[MCOM_CHANNEL_LEN], unsigned char cap);
01463
01466 char* LastData() { return data.data; }
01467
01470 int LastMsgType() { return type; }
01471
01474 char* LastChannel() { return channel; }
01475
01476 void FillData(player_msghdr_t hdr, const char* buffer);
01477 void Print();
01478 };
01479
01480 #endif
01481
01485 class PlannerProxy : public ClientProxy
01486 {
01487
01488 private:
01489
01490 void Subscribe(uint aIndex);
01491 void Unsubscribe();
01492
01493
01494 playerc_planner_t *mDevice;
01495
01496 public:
01497
01499 PlannerProxy(PlayerClient *aPc, uint aIndex=0);
01501 ~PlannerProxy();
01502
01504 void SetGoalPose(double aGx, double aGy, double aGa);
01505
01508 void RequestWaypoints();
01509
01512 void SetEnable(bool aEnable);
01513
01515 uint GetPathValid() const { return GetVar(mDevice->path_valid); };
01516
01518 uint GetPathDone() const { return GetVar(mDevice->path_done); };
01519
01521 double GetPx() const { return GetVar(mDevice->px); };
01523 double GetPy() const { return GetVar(mDevice->py); };
01525 double GetPz() const { return GetVar(mDevice->pa); };
01526
01528 double GetGx() const { return GetVar(mDevice->gx); };
01530 double GetGy() const { return GetVar(mDevice->gy); };
01532 double GetGz() const { return GetVar(mDevice->ga); };
01533
01535 double GetWx() const { return GetVar(mDevice->wx); };
01537 double GetWy() const { return GetVar(mDevice->wy); };
01539 double GetWz() const { return GetVar(mDevice->wa); };
01540
01544 uint GetCurrentWaypoint() const
01545 { return GetVar(mDevice->curr_waypoint); };
01546
01548 uint GetWaypointCount() const
01549 { return GetVar(mDevice->waypoint_count); };
01550
01551
01552
01553
01554
01555 };
01556
01561 class Position2dProxy : public ClientProxy
01562 {
01563
01564 private:
01565
01566 void Subscribe(uint aIndex);
01567 void Unsubscribe();
01568
01569
01570 playerc_position2d_t *mDevice;
01571
01572 public:
01573
01575 Position2dProxy(PlayerClient *aPc, uint aIndex=0);
01577 ~Position2dProxy();
01578
01582 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed);
01583
01586 void SetSpeed(double aXSpeed, double aYawSpeed)
01587 { return SetSpeed(aXSpeed, 0, aYawSpeed);}
01588
01591 void GoTo(double aX, double aY, double aYaw);
01592
01594 void SetCarlike(double aXSpeed, double aDriveAngle);
01595
01598 void RequestGeom();
01599
01601 player_pose_t GetPose()
01602 {
01603 player_pose_t p;
01604 scoped_lock_t lock(mPc->mMutex);
01605 p.px = mDevice->pose[0];
01606 p.py = mDevice->pose[1];
01607 p.pa = mDevice->pose[2];
01608 return(p);
01609 }
01610
01612 player_bbox_t GetSize()
01613 {
01614 player_bbox_t b;
01615 scoped_lock_t lock(mPc->mMutex);
01616 b.sl = mDevice->size[0];
01617 b.sw = mDevice->size[1];
01618 return(b);
01619 }
01620
01625 void SetMotorEnable(bool enable);
01626
01635
01636
01638 void ResetOdometry();
01639
01642
01643
01646 void SetOdometry(double aX, double aY, double aYaw);
01647
01649
01650
01652
01653
01656
01657
01659
01660
01662
01663
01665
01666
01668
01669
01671
01672
01674 double GetXPos() const { return GetVar(mDevice->px); };
01675
01677 double GetYPos() const { return GetVar(mDevice->py); };
01678
01680 double GetYaw() const { return GetVar(mDevice->pa); };
01681
01683 double GetXSpeed() const { return GetVar(mDevice->vx); };
01684
01686 double GetYSpeed() const { return GetVar(mDevice->vy); };
01687
01689 double GetYawSpeed() const { return GetVar(mDevice->va); };
01690
01692 bool GetStall() const { return GetVar(mDevice->stall); };
01693
01694 };
01695
01702 class Position3dProxy : public ClientProxy
01703 {
01704
01705 private:
01706
01707 void Subscribe(uint aIndex);
01708 void Unsubscribe();
01709
01710
01711 playerc_position3d_t *mDevice;
01712
01713 public:
01714
01716 Position3dProxy(PlayerClient *aPc, uint aIndex=0);
01718 ~Position3dProxy();
01719
01723 void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed,
01724 double aRollSpeed, double aPitchSpeed, double aYawSpeed);
01725
01729 void SetSpeed(double aXSpeed, double aYSpeed,
01730 double aZSpeed, double aYawSpeed)
01731 { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
01732
01734 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
01735 { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
01736
01739 void SetSpeed(double aXSpeed, double aYawSpeed)
01740 { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
01741
01742
01745 void GoTo(double aX, double aY, double aZ,
01746 double aRoll, double aPitch, double aYaw);
01747
01752 void SetMotorEnable(bool aEnable);
01753
01756
01757
01759
01760
01764
01765
01766
01769
01770
01772
01773
01775
01776
01779
01780
01782 double GetXPos() const { return GetVar(mDevice->pos_x); };
01783
01785 double GetYPos() const { return GetVar(mDevice->pos_y); };
01786
01788 double GetZPos() const { return GetVar(mDevice->pos_z); };
01789
01791 double GetRoll() const { return GetVar(mDevice->pos_roll); };
01792
01794 double GetPitch() const { return GetVar(mDevice->pos_pitch); };
01795
01797 double GetYaw() const { return GetVar(mDevice->pos_yaw); };
01798
01800 double GetXSpeed() const { return GetVar(mDevice->vel_x); };
01801
01803 double GetYSpeed() const { return GetVar(mDevice->vel_y); };
01804
01806 double GetZSpeed() const { return GetVar(mDevice->vel_z); };
01807
01809 double GetRollSpeed() const { return GetVar(mDevice->vel_roll); };
01810
01812 double GetPitchSpeed() const { return GetVar(mDevice->vel_pitch); };
01813
01815 double GetYawSpeed() const { return GetVar(mDevice->vel_yaw); };
01816
01818 bool GetStall () const { return GetVar(mDevice->stall); };
01819 };
01820
01823 class PowerProxy : public ClientProxy
01824 {
01825 private:
01826
01827 void Subscribe(uint aIndex);
01828 void Unsubscribe();
01829
01830
01831 playerc_power_t *mDevice;
01832
01833 public:
01835 PowerProxy(PlayerClient *aPc, uint aIndex=0);
01837 ~PowerProxy();
01838
01840 double GetCharge() const { return GetVar(mDevice->charge); };
01841
01842 };
01843
01850 class PtzProxy : public ClientProxy
01851 {
01852
01853 private:
01854
01855 void Subscribe(uint aIndex);
01856 void Unsubscribe();
01857
01858
01859 playerc_ptz_t *mDevice;
01860
01861 public:
01863 PtzProxy(PlayerClient *aPc, uint aIndex=0);
01864
01865 ~PtzProxy();
01866
01867 public:
01868
01872 void SetCam(double aPan, double aTilt, double aZoom);
01873
01875 void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0);
01876
01879
01880
01882 double GetPan() const { return GetVar(mDevice->pan); };
01884 double GetTilt() const { return GetVar(mDevice->tilt); };
01886 double GetZoom() const { return GetVar(mDevice->zoom); };
01887
01888 };
01889
01894 class SimulationProxy : public ClientProxy
01895 {
01896 private:
01897
01898 void Subscribe(uint aIndex);
01899 void Unsubscribe();
01900
01901
01902 playerc_simulation_t *mDevice;
01903
01904 public:
01906 SimulationProxy(PlayerClient *aPc, uint aIndex=0);
01908 ~SimulationProxy();
01909
01912 void SetPose2d(char* identifier, double x, double y, double a);
01913
01916 void GetPose2d(char* identifier, double& x, double& y, double& a);
01917 };
01918
01919
01925 class SonarProxy : public ClientProxy
01926 {
01927 private:
01928
01929 void Subscribe(uint aIndex);
01930 void Unsubscribe();
01931
01932
01933 playerc_sonar_t *mDevice;
01934
01935 public:
01937 SonarProxy(PlayerClient *aPc, uint aIndex=0);
01939 ~SonarProxy();
01940
01942 uint GetCount() const { return GetVar(mDevice->scan_count); };
01943
01945 double GetScan(uint aIndex) const
01946 { return GetVar(mDevice->scan[aIndex]); };
01949 double operator [] (uint aIndex) const { return GetScan(aIndex); }
01950
01952 uint GetPoseCount() const { return GetVar(mDevice->pose_count); };
01953
01955 player_pose_t GetPose(uint aIndex) const
01956 { return GetVar(mDevice->poses[aIndex]); };
01957
01963
01964
01966 void RequestGeom();
01967 };
01968
01969 #if 0
01970
01974 class SoundProxy : public ClientProxy
01975 {
01976
01977 private:
01978
01979 void Subscribe(uint aIndex);
01980 void Unsubscribe();
01981
01982
01983 playerc_sound_t *mDevice;
01984
01985 public:
01986
01987 SoundProxy(PlayerClient *aPc, uint aIndex=0);
01988
01989 ~SoundProxy();
01990
01992 void Play(int aIndex);
01993 };
01994 #endif
01995
02000 class SpeechProxy : public ClientProxy
02001 {
02002
02003 private:
02004
02005 void Subscribe(uint aIndex);
02006 void Unsubscribe();
02007
02008
02009 playerc_speech_t *mDevice;
02010
02011 public:
02013 SpeechProxy(PlayerClient *aPc, uint aIndex=0);
02015 ~SpeechProxy();
02016
02019 void Say(std::string aStr);
02020 };
02021
02022 #if 0
02023
02026 class SpeechRecognitionProxy : public ClientProxy
02027 {
02028
02029 private:
02030
02031 void Subscribe(uint aIndex);
02032 void Unsubscribe();
02033
02034
02035 playerc_speech_t *mDevice;
02036
02037 public:
02038
02039 SpeechRecognitionProxy(PlayerClient *aPc, uint aIndex=0);
02040
02041 ~SpeechRecognitionProxy();
02042
02043 std::string GetText();
02044
02045 };
02046 #endif
02047
02048 #if 0
02049
02058 class TruthProxy : public ClientProxy
02059 {
02060
02061 private:
02062
02063 void Subscribe(uint aIndex);
02064 void Unsubscribe();
02065
02066
02067 playerc_truth_t *mDevice;
02068
02069 public:
02071 TruthProxy(PlayerClient *aPc, uint aIndex=0);
02073 ~TruthProxy();
02074
02076 double GetX() const { return GetVar(mDevice->pos[0]); };
02078 double GetY() const { return GetVar(mDevice->pos[1]); };
02080 double GetZ() const { return GetVar(mDevice->pos[2]); };
02082 double GetRoll() const { return GetVar(mDevice->rot[0]); };
02084 double GetPitch() const { return GetVar(mDevice->rot[1]); };
02086 double GetYaw() const { return GetVar(mDevice->rot[2]); };
02087
02092 void GetPose(double *px, double *py, double *pz,
02093 double *rx, double *ry, double *rz);
02094
02096 void SetPose(double px, double py, double pz,
02097 double rx, double ry, double rz);
02098
02100 void SetPoseOnRoot(double px, double py, double pz,
02101 double rx, double ry, double rz);
02102
02106 uint GetFiducialID();
02107
02111 void SetFiducialID(int16_t id);
02112
02113 };
02117 class WaveformProxy : public ClientProxy
02118 {
02119
02120 private:
02121
02122 void Subscribe(uint aIndex);
02123 void Unsubscribe();
02124
02125
02126 playerc_waveform_t *mDevice;
02127
02128 public:
02129
02130 WaveformProxy(PlayerClient *aPc, uint aIndex=0);
02131
02132 ~WaveformProxy();
02133
02134 uint GetCount() const { return GetVar(mDevice->data_count); };
02135
02137 uint GetBitRate() const { return GetVar(mDevice->rate); };
02138
02140 uint GetDepth() const { return GetVar(mDevice->depth); };
02141
02143 void GetImage(uint8_t* aBuffer) const
02144 {
02145 return GetVarByRef(mDevice->data,
02146 mDevice->data+GetCount(),
02147 aBuffer);
02148 };
02149
02150
02151
02152
02153
02154 void ConfigureDSP(uint aBitRate, uint aDepth);
02155
02156
02157 void OpenDSPforWrite();
02158
02159
02160 void Play();
02161 };
02162 #endif
02163
02166 class WiFiProxy: public ClientProxy
02167 {
02168
02169 private:
02170
02171 void Subscribe(uint aIndex);
02172 void Unsubscribe();
02173
02174
02175 playerc_wifi_t *mDevice;
02176
02177 public:
02179 WiFiProxy(PlayerClient *aPc, uint aIndex=0);
02181 ~WiFiProxy();
02182
02183 #if 0
02184
02185 int GetLinkQuality(char
02186 int GetLevel(char
02187 int GetLeveldBm(char
02188 int GetNoise(char
02189 int GetNoisedBm(char
02190
02191 uint16_t GetMaxLinkQuality() { return maxqual; }
02192 uint8_t GetMode() { return op_mode; }
02193
02194 int GetBitrate();
02195
02196 char
02197
02198 char
02199 char
02200
02201 int AddSpyHost(char *address);
02202 int RemoveSpyHost(char *address);
02203
02204 private:
02205 int GetLinkIndex(char *ip);
02206
02208 int link_count;
02209 player_wifi_link_t links[PLAYER_WIFI_MAX_LINKS];
02210 uint32_t throughput;
02211 uint8_t op_mode;
02212 int32_t bitrate;
02213 uint16_t qual_type, maxqual, maxlevel, maxnoise;
02214
02215 char access_point[32];
02216 #endif
02217 };
02220 class RFIDProxy : public ClientProxy
02221 {
02222
02223 private:
02224
02225 void Subscribe(uint aIndex);
02226 void Unsubscribe();
02227
02228
02229 playerc_rfid_t *mDevice;
02230
02231 public:
02233 RFIDProxy(PlayerClient *aPc, uint aIndex=0);
02235 ~RFIDProxy();
02236
02238 uint GetTagsCount() const { return GetVar(mDevice->tags_count); };
02240 playerc_rfidtag_t GetRFIDTag(uint aIndex) const
02241 { return GetVar(mDevice->tags[aIndex]);};
02242
02247 playerc_rfidtag_t operator [](uint aIndex) const
02248 { return(GetRFIDTag(aIndex)); }
02249 };
02252 }
02253
02254
02261 namespace std
02262 {
02263 std::ostream& operator << (std::ostream& os, const player_point_2d_t& c);
02264 std::ostream& operator << (std::ostream& os, const player_pose_t& c);
02265 std::ostream& operator << (std::ostream& os, const player_pose3d_t& c);
02266 std::ostream& operator << (std::ostream& os, const player_bbox_t& c);
02267 std::ostream& operator << (std::ostream& os, const player_segment_t& c);
02268 std::ostream& operator << (std::ostream& os, const playerc_device_info_t& c);
02269
02270 std::ostream& operator << (std::ostream& os, const PlayerCc::ClientProxy& c);
02271 std::ostream& operator << (std::ostream& os, const PlayerCc::ActArrayProxy& c);
02272 std::ostream& operator << (std::ostream& os, const PlayerCc::AioProxy& c);
02273
02274
02275
02276 std::ostream& operator << (std::ostream& os, const PlayerCc::BlobfinderProxy& c);
02277 std::ostream& operator << (std::ostream& os, const PlayerCc::BumperProxy& c);
02278 std::ostream& operator << (std::ostream& os, const PlayerCc::CameraProxy& c);
02279 std::ostream& operator << (std::ostream& os, const PlayerCc::DioProxy& c);
02280
02281 std::ostream& operator << (std::ostream& os, const PlayerCc::FiducialProxy& c);
02282 std::ostream& operator << (std::ostream& os, const PlayerCc::GpsProxy& c);
02283 std::ostream& operator << (std::ostream& os, const PlayerCc::GripperProxy& c);
02284 std::ostream& operator << (std::ostream& os, const PlayerCc::IrProxy& c);
02285 std::ostream& operator << (std::ostream& os, const PlayerCc::LaserProxy& c);
02286 std::ostream& operator << (std::ostream& os, const PlayerCc::LimbProxy& c);
02287 std::ostream& operator << (std::ostream& os, const PlayerCc::LocalizeProxy& c);
02288 std::ostream& operator << (std::ostream& os, const PlayerCc::LogProxy& c);
02289 std::ostream& operator << (std::ostream& os, const PlayerCc::MapProxy& c);
02290 std::ostream& operator << (std::ostream& os, const PlayerCc::PlannerProxy& c);
02291
02292 std::ostream& operator << (std::ostream& os, const PlayerCc::Position2dProxy& c);
02293 std::ostream& operator << (std::ostream& os, const PlayerCc::Position3dProxy& c);
02294 std::ostream& operator << (std::ostream& os, const PlayerCc::PowerProxy& c);
02295 std::ostream& operator << (std::ostream& os, const PlayerCc::PtzProxy& c);
02296 std::ostream& operator << (std::ostream& os, const PlayerCc::SimulationProxy& c);
02297 std::ostream& operator << (std::ostream& os, const PlayerCc::SonarProxy& c);
02298
02299 std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechProxy& c);
02300
02301
02302 std::ostream& operator << (std::ostream& os, const PlayerCc::WiFiProxy& c);
02303 std::ostream& operator << (std::ostream& os, const PlayerCc::RFIDProxy& c);
02304
02305 }
02310 #endif
02311