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 8173 2009-08-04 07:25:00Z gbiggs $ 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); 00168 00170 void MoveTo(uint32_t aJoint, float aPos); 00172 void MoveToMulti(std::vector<float> aPos); 00174 void MoveAtSpeed(uint32_t aJoint, float aSpeed); 00176 void MoveAtSpeedMulti(std::vector<float> aSpeed); 00178 void MoveHome(int aJoint); 00180 void SetActuatorCurrent(uint32_t aJoint, float aCurrent); 00182 void SetActuatorCurrentMulti(std::vector<float> aCurrent); 00183 00185 uint32_t GetCount(void) const { return GetVar(mDevice->actuators_count); } 00187 player_actarray_actuator_t GetActuatorData(uint32_t aJoint) const; 00189 player_actarray_actuatorgeom_t GetActuatorGeom(uint32_t aJoint) const; 00191 player_point_3d_t GetBasePos(void) const { return GetVar(mDevice->base_pos); } 00193 player_orientation_3d_t GetBaseOrientation(void) const { return GetVar(mDevice->base_orientation); } 00194 00195 00200 player_actarray_actuator_t operator [](uint32_t aJoint) 00201 { return(GetActuatorData(aJoint)); } 00202 }; 00203 00207 class PLAYERCC_EXPORT AioProxy : public ClientProxy 00208 { 00209 private: 00210 00211 void Subscribe(uint32_t aIndex); 00212 void Unsubscribe(); 00213 00214 // libplayerc data structure 00215 playerc_aio_t *mDevice; 00216 00217 public: 00218 00219 AioProxy (PlayerClient *aPc, uint32_t aIndex=0); 00220 ~AioProxy(); 00221 00223 uint32_t GetCount() const { return(GetVar(mDevice->voltages_count)); }; 00224 00226 double GetVoltage(uint32_t aIndex) const 00227 { return(GetVar(mDevice->voltages[aIndex])); }; 00228 00230 void SetVoltage(uint32_t aIndex, double aVoltage); 00231 00236 double operator [](uint32_t aIndex) const 00237 { return GetVoltage(aIndex); } 00238 00239 }; 00240 00241 00245 class PLAYERCC_EXPORT AudioProxy : public ClientProxy 00246 { 00247 00248 private: 00249 00250 void Subscribe(uint32_t aIndex); 00251 void Unsubscribe(); 00252 00253 // libplayerc data structure 00254 playerc_audio_t *mDevice; 00255 00256 public: 00257 00258 AudioProxy(PlayerClient *aPc, uint32_t aIndex=0); 00259 ~AudioProxy(); 00260 00262 uint32_t GetMixerDetailsCount() const {return(GetVar(mDevice->channel_details_list.details_count));}; 00264 player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const {return(GetVar(mDevice->channel_details_list.details[aIndex]));}; 00266 uint32_t GetDefaultOutputChannel() const {return(GetVar(mDevice->channel_details_list.default_output));}; 00268 uint32_t GetDefaultInputChannel() const {return(GetVar(mDevice->channel_details_list.default_input));}; 00269 00271 uint32_t GetWavDataLength() const {return(GetVar(mDevice->wav_data.data_count));}; 00276 void GetWavData(uint8_t* aData) const 00277 { 00278 return GetVarByRef(mDevice->wav_data.data, 00279 mDevice->wav_data.data+GetWavDataLength(), 00280 aData); 00281 }; 00282 00284 uint32_t GetSeqCount() const {return(GetVar(mDevice->seq_data.tones_count));}; 00286 player_audio_seq_item_t GetSeqItem(int aIndex) const {return(GetVar(mDevice->seq_data.tones[aIndex]));}; 00287 00289 uint32_t GetChannelCount() const {return(GetVar(mDevice->mixer_data.channels_count));}; 00291 player_audio_mixer_channel_t GetChannel(int aIndex) const {return(GetVar(mDevice->mixer_data.channels[aIndex]));}; 00293 uint32_t GetState(void) const {return(GetVar(mDevice->state));}; 00294 00295 00296 00298 void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat); 00299 00301 void SetWavStremRec(bool aState); 00302 00304 void PlaySample(int aIndex); 00305 00307 void PlaySeq(player_audio_seq_t * aTones); 00308 00310 void SetMultMixerLevels(player_audio_mixer_channel_list_t * aLevels); 00311 00313 void SetMixerLevel(uint32_t index, float amplitude, uint8_t active); 00314 00317 void RecordWav(); 00318 00320 void LoadSample(int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat); 00321 00324 void GetSample(int aIndex); 00325 00327 void RecordSample(int aIndex, uint32_t aLength); 00328 00331 void GetMixerLevels(); 00332 00335 void GetMixerDetails(); 00336 00337 }; 00338 00346 class PLAYERCC_EXPORT BlackBoardProxy : public ClientProxy 00347 { 00348 private: 00349 void Subscribe(uint32_t aIndex); 00350 void Unsubscribe(); 00351 00352 // libplayerc data structure 00353 playerc_blackboard_t *mDevice; 00354 00355 public: 00357 BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0); 00359 ~BlackBoardProxy(); 00361 player_blackboard_entry_t *SubscribeToKey(const char *key, const char* group = ""); 00363 void UnsubscribeFromKey(const char *key, const char* group = ""); 00365 void SubscribeToGroup(const char* key); 00367 void UnsubscribeFromGroup(const char* group); 00369 void SetEntry(const player_blackboard_entry_t &entry); 00371 player_blackboard_entry_t *GetEntry(const char* key, const char* group); 00373 void SetEventHandler(void (*on_blackboard_event)(playerc_blackboard_t *, player_blackboard_entry_t)); 00374 }; 00375 00376 // /** 00377 // The @p BlinkenlightProxy class is used to enable and disable 00378 // a flashing indicator light, and to set its period, via a @ref 00379 // interface_blinkenlight device */ 00380 // class PLAYERCC_EXPORT BlinkenLightProxy : public ClientProxy 00381 // { 00382 // private: 00383 // 00384 // void Subscribe(uint32_t aIndex); 00385 // void Unsubscribe(); 00386 // 00387 // // libplayerc data structure 00388 // playerc_blinkenlight_t *mDevice; 00389 // 00390 // public: 00391 // /** Constructor. 00392 // Leave the access field empty to start unconnected. 00393 // */ 00394 // BlinkenLightProxy(PlayerClient *aPc, uint32_t aIndex=0); 00395 // ~BlinkenLightProxy(); 00396 // 00397 // // true: indicator light enabled, false: disabled. 00398 // bool GetEnable(); 00399 // 00400 // /** The current period (one whole on/off cycle) of the blinking 00401 // light. If the period is zero and the light is enabled, the light 00402 // is on. 00403 // */ 00404 // void SetPeriod(double aPeriod); 00405 // 00406 // /** Set the state of the indicator light. A period of zero means 00407 // the light will be unblinkingly on or off. Returns 0 on 00408 // success, else -1. 00409 // */ 00410 // void SetEnable(bool aSet); 00411 // }; 00412 00419 class PLAYERCC_EXPORT BlobfinderProxy : public ClientProxy 00420 { 00421 private: 00422 00423 void Subscribe(uint32_t aIndex); 00424 void Unsubscribe(); 00425 00426 // libplayerc data structure 00427 playerc_blobfinder_t *mDevice; 00428 00429 public: 00431 BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0); 00433 ~BlobfinderProxy(); 00434 00436 uint32_t GetCount() const { return GetVar(mDevice->blobs_count); }; 00438 playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const 00439 { return GetVar(mDevice->blobs[aIndex]);}; 00440 00442 uint32_t GetWidth() const { return GetVar(mDevice->width); }; 00444 uint32_t GetHeight() const { return GetVar(mDevice->height); }; 00445 00450 playerc_blobfinder_blob_t operator [](uint32_t aIndex) const 00451 { return(GetBlob(aIndex)); } 00452 00453 /* 00455 void SetTrackingColor(uint32_t aReMin=0, uint32_t aReMax=255, uint32_t aGrMin=0, 00456 uint32_t aGrMax=255, uint32_t aBlMin=0, uint32_t aBlMax=255); 00457 void SetImagerParams(int aContrast, int aBrightness, 00458 int aAutogain, int aColormode); 00459 void SetContrast(int aC); 00460 void SetColorMode(int aM); 00461 void SetBrightness(int aB); 00462 void SetAutoGain(int aG);*/ 00463 00464 }; 00465 00470 class PLAYERCC_EXPORT BumperProxy : public ClientProxy 00471 { 00472 00473 private: 00474 00475 void Subscribe(uint32_t aIndex); 00476 void Unsubscribe(); 00477 00478 // libplayerc data structure 00479 playerc_bumper_t *mDevice; 00480 00481 public: 00482 00483 BumperProxy(PlayerClient *aPc, uint32_t aIndex=0); 00484 ~BumperProxy(); 00485 00486 uint32_t GetCount() const { return GetVar(mDevice->bumper_count); }; 00487 00489 uint32_t IsBumped(uint32_t aIndex) const 00490 { return GetVar(mDevice->bumpers[aIndex]); }; 00491 00493 bool IsAnyBumped(); 00494 00496 void RequestBumperConfig(); 00497 00499 uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); }; 00500 00502 player_bumper_define_t GetPose(uint32_t aIndex) const 00503 { return GetVar(mDevice->poses[aIndex]); }; 00504 00509 bool operator [](uint32_t aIndex) const 00510 { return IsBumped(aIndex) != 0 ? true : false; } 00511 00512 }; 00513 00517 class PLAYERCC_EXPORT CameraProxy : public ClientProxy 00518 { 00519 00520 private: 00521 00522 virtual void Subscribe(uint32_t aIndex); 00523 virtual void Unsubscribe(); 00524 00525 // libplayerc data structure 00526 playerc_camera_t *mDevice; 00527 00528 std::string mPrefix; 00529 int mFrameNo; 00530 00531 public: 00532 00534 CameraProxy (PlayerClient *aPc, uint32_t aIndex=0); 00535 00536 virtual ~CameraProxy(); 00537 00541 void SaveFrame(const std::string aPrefix, uint32_t aWidth=4); 00542 00544 void Decompress(); 00545 00547 uint32_t GetDepth() const { return GetVar(mDevice->bpp); }; 00548 00550 uint32_t GetWidth() const { return GetVar(mDevice->width); }; 00551 00553 uint32_t GetHeight() const { return GetVar(mDevice->height); }; 00554 00561 uint32_t GetFormat() const { return GetVar(mDevice->format); }; 00562 00564 uint32_t GetImageSize() const { return GetVar(mDevice->image_count); }; 00565 00570 void GetImage(uint8_t* aImage) const 00571 { 00572 return GetVarByRef(mDevice->image, 00573 mDevice->image+GetVar(mDevice->image_count), 00574 aImage); 00575 }; 00576 00581 uint32_t GetCompression() const { return GetVar(mDevice->compression); }; 00582 00583 }; 00584 00585 00590 class PLAYERCC_EXPORT DioProxy : public ClientProxy 00591 { 00592 private: 00593 00594 void Subscribe(uint32_t aIndex); 00595 void Unsubscribe(); 00596 00597 // libplayerc data structure 00598 playerc_dio_t *mDevice; 00599 00600 public: 00602 DioProxy(PlayerClient *aPc, uint32_t aIndex=0); 00604 ~DioProxy(); 00605 00607 uint32_t GetCount() const { return GetVar(mDevice->count); }; 00608 00610 uint32_t GetDigin() const { return GetVar(mDevice->digin); }; 00611 00613 bool GetInput(uint32_t aIndex) const; 00614 00616 void SetOutput(uint32_t aCount, uint32_t aDigout); 00617 00622 uint32_t operator [](uint32_t aIndex) const 00623 { return GetInput(aIndex); } 00624 }; 00625 00631 class PLAYERCC_EXPORT FiducialProxy : public ClientProxy 00632 { 00633 private: 00634 void Subscribe(uint32_t aIndex); 00635 void Unsubscribe(); 00636 00637 // libplayerc data structure 00638 playerc_fiducial_t *mDevice; 00639 00640 public: 00642 FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0); 00644 ~FiducialProxy(); 00645 00647 uint32_t GetCount() const { return GetVar(mDevice->fiducials_count); }; 00648 00650 player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const 00651 { return GetVar(mDevice->fiducials[aIndex]);}; 00652 00654 player_pose3d_t GetSensorPose() const 00655 { return GetVar(mDevice->fiducial_geom.pose);}; 00656 00658 player_bbox3d_t GetSensorSize() const 00659 { return GetVar(mDevice->fiducial_geom.size);}; 00660 00662 player_bbox2d_t GetFiducialSize() const 00663 { return GetVar(mDevice->fiducial_geom.fiducial_size);}; 00664 00666 void RequestGeometry(); 00667 00672 player_fiducial_item_t operator [](uint32_t aIndex) const 00673 { return GetFiducialItem(aIndex); } 00674 }; 00675 00679 class PLAYERCC_EXPORT GpsProxy : public ClientProxy 00680 { 00681 00682 private: 00683 00684 void Subscribe(uint32_t aIndex); 00685 void Unsubscribe(); 00686 00687 // libplayerc data structure 00688 playerc_gps_t *mDevice; 00689 00690 public: 00691 00692 // Constructor 00693 GpsProxy(PlayerClient *aPc, uint32_t aIndex=0); 00694 00695 ~GpsProxy(); 00696 00698 double GetLatitude() const { return GetVar(mDevice->lat); }; 00699 double GetLongitude() const { return GetVar(mDevice->lon); }; 00700 00702 double GetAltitude() const { return GetVar(mDevice->alt); }; 00703 00705 uint32_t GetSatellites() const { return GetVar(mDevice->sat_count); }; 00706 00708 uint32_t GetQuality() const { return GetVar(mDevice->quality); }; 00709 00711 double GetHdop() const { return GetVar(mDevice->hdop); }; 00712 00714 double GetVdop() const { return GetVar(mDevice->vdop); }; 00715 00717 double GetUtmEasting() const { return GetVar(mDevice->utm_e); }; 00718 double GetUtmNorthing() const { return GetVar(mDevice->utm_n); }; 00719 00721 double GetTime() const { return GetVar(mDevice->utc_time); }; 00722 00724 double GetErrHorizontal() const { return GetVar(mDevice->err_horz); }; 00725 double GetErrVertical() const { return GetVar(mDevice->err_vert); }; 00726 }; 00727 00735 class PLAYERCC_EXPORT Graphics2dProxy : public ClientProxy 00736 { 00737 00738 private: 00739 00740 // Subscribe 00741 void Subscribe(uint32_t aIndex); 00742 // Unsubscribe 00743 void Unsubscribe(); 00744 00745 // libplayerc data structure 00746 playerc_graphics2d_t *mDevice; 00747 00748 public: 00749 // Constructor 00750 Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0); 00751 // Destructor 00752 ~Graphics2dProxy(); 00753 00755 void Color(player_color_t col); 00756 00758 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha); 00759 00761 void Clear(void); 00762 00764 void DrawPoints(player_point_2d_t pts[], int count); 00765 00767 void DrawPolygon(player_point_2d_t pts[], 00768 int count, 00769 bool filled, 00770 player_color_t fill_color); 00771 00773 void DrawPolyline(player_point_2d_t pts[], int count); 00774 }; 00775 00781 class PLAYERCC_EXPORT Graphics3dProxy : public ClientProxy 00782 { 00783 00784 private: 00785 00786 // Subscribe 00787 void Subscribe(uint32_t aIndex); 00788 // Unsubscribe 00789 void Unsubscribe(); 00790 00791 // libplayerc data structure 00792 playerc_graphics3d_t *mDevice; 00793 00794 public: 00795 // Constructor 00796 Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0); 00797 // Destructor 00798 ~Graphics3dProxy(); 00799 00801 void Color(player_color_t col); 00802 00804 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha); 00805 00807 void Clear(void); 00808 00810 void Draw(player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count); 00811 00812 }; 00813 00818 class PLAYERCC_EXPORT GripperProxy : public ClientProxy 00819 { 00820 00821 private: 00822 00823 void Subscribe(uint32_t aIndex); 00824 void Unsubscribe(); 00825 00826 // libplayerc data structure 00827 playerc_gripper_t *mDevice; 00828 00829 public: 00830 00832 GripperProxy(PlayerClient *aPc, uint32_t aIndex=0); 00834 ~GripperProxy(); 00835 00838 void RequestGeometry(void); 00839 00841 uint32_t GetState() const { return GetVar(mDevice->state); }; 00843 uint32_t GetBeams() const { return GetVar(mDevice->beams); }; 00845 player_pose3d_t GetPose() const { return GetVar(mDevice->pose); }; 00847 player_bbox3d_t GetOuterSize() const { return GetVar(mDevice->outer_size); }; 00849 player_bbox3d_t GetInnerSize() const { return GetVar(mDevice->inner_size); }; 00851 uint32_t GetNumBeams() const { return GetVar(mDevice->num_beams); }; 00853 uint32_t GetCapacity() const { return GetVar(mDevice->capacity); }; 00855 uint32_t GetStored() const { return GetVar(mDevice->stored); }; 00856 00858 void Open(); 00860 void Close(); 00862 void Stop(); 00864 void Store(); 00866 void Retrieve(); 00867 }; 00868 00871 class PLAYERCC_EXPORT HealthProxy : public ClientProxy 00872 { 00873 00874 private: 00875 00876 void Subscribe(uint32_t aIndex); 00877 void Unsubscribe(); 00878 00879 // libplayerc data structure 00880 playerc_health_t *mDevice; 00881 00882 public: 00884 HealthProxy(PlayerClient *aPc, uint32_t aIndex=0); 00886 ~HealthProxy(); 00887 00889 float GetIdleCPU(); 00890 00892 float GetSystemCPU(); 00893 00895 float GetUserCPU(); 00896 00898 int64_t GetMemTotal(); 00899 00901 int64_t GetMemUsed(); 00902 00904 int64_t GetMemFree(); 00905 00907 int64_t GetSwapTotal(); 00908 00910 int64_t GetSwapUsed(); 00911 00913 int64_t GetSwapFree(); 00914 00916 float GetPercMemUsed(); 00917 00919 float GetPercSwapUsed(); 00920 00922 float GetPercTotalUsed(); 00923 }; 00924 00925 00926 00931 class PLAYERCC_EXPORT ImuProxy : public ClientProxy 00932 { 00933 private: 00934 void Subscribe(uint32_t aIndex); 00935 void Unsubscribe(); 00936 00937 // libplayerc data structure 00938 playerc_imu_t *mDevice; 00939 00940 public: 00941 00943 ImuProxy(PlayerClient *aPc, uint32_t aIndex=0); 00945 ~ImuProxy(); 00946 00948 player_pose3d_t GetPose() const { return GetVar(mDevice->pose); }; 00950 float GetXAccel(); 00951 float GetYAccel(); 00952 float GetZAccel(); 00953 float GetXGyro(); 00954 float GetYGyro(); 00955 float GetZGyro(); 00956 float GetXMagn(); 00957 float GetYMagn(); 00958 float GetZMagn(); 00959 00960 player_imu_data_calib_t GetRawValues() const 00961 { return GetVar(mDevice->calib_data); }; 00962 00964 void SetDatatype(int aDatatype); 00965 00967 void ResetOrientation(int aValue); 00968 00969 00970 }; 00971 00972 00977 class PLAYERCC_EXPORT IrProxy : public ClientProxy 00978 { 00979 00980 private: 00981 00982 void Subscribe(uint32_t aIndex); 00983 void Unsubscribe(); 00984 00985 // libplayerc data structure 00986 playerc_ir_t *mDevice; 00987 00988 public: 00989 00991 IrProxy(PlayerClient *aPc, uint32_t aIndex=0); 00993 ~IrProxy(); 00994 00996 uint32_t GetCount() const { return GetVar(mDevice->data.ranges_count); }; 00998 double GetRange(uint32_t aIndex) const 00999 { return GetVar(mDevice->data.ranges[aIndex]); }; 01001 double GetVoltage(uint32_t aIndex) const 01002 { return GetVar(mDevice->data.voltages[aIndex]); }; 01004 uint32_t GetPoseCount() const { return GetVar(mDevice->poses.poses_count); }; 01006 player_pose3d_t GetPose(uint32_t aIndex) const 01007 {return GetVar(mDevice->poses.poses[aIndex]);}; 01008 01010 void RequestGeom(); 01011 01016 double operator [](uint32_t aIndex) const 01017 { return GetRange(aIndex); } 01018 01019 }; 01020 01026 class PLAYERCC_EXPORT LaserProxy : public ClientProxy 01027 { 01028 private: 01029 01030 void Subscribe(uint32_t aIndex); 01031 void Unsubscribe(); 01032 01033 // libplayerc data structure 01034 playerc_laser_t *mDevice; 01035 01036 // local storage of config 01037 double min_angle, max_angle, scan_res, range_res, scanning_frequency; 01038 bool intensity; 01039 01040 public: 01041 01043 LaserProxy(PlayerClient *aPc, uint32_t aIndex=0); 01045 ~LaserProxy(); 01046 01048 uint32_t GetCount() const { return GetVar(mDevice->scan_count); }; 01049 01051 double GetMaxRange() const { return GetVar(mDevice->max_range); }; 01052 01054 double GetScanRes() const { return GetVar(mDevice->scan_res); }; 01055 01057 double GetRangeRes() const { return GetVar(mDevice->range_res); }; 01058 01060 double GetScanningFrequency() const { return GetVar(mDevice->scanning_frequency); }; 01061 01063 double GetMinAngle() const { return GetVar(mDevice->scan_start); }; 01065 double GetMaxAngle() const 01066 { 01067 scoped_lock_t lock(mPc->mMutex); 01068 return mDevice->scan_start + (mDevice->scan_count - 1)*mDevice->scan_res; 01069 }; 01070 01072 double GetConfMinAngle() const { return min_angle; }; 01074 double GetConfMaxAngle() const { return max_angle; }; 01075 01077 bool IntensityOn() const { return GetVar(mDevice->intensity_on) != 0 ? true : false; }; 01078 01079 // /// Scan data (polar): range (m) and bearing (radians) 01080 // double GetScan(uint32_t aIndex) const 01081 // { return GetVar(mDevice->scan[aIndex]); }; 01082 01084 player_point_2d_t GetPoint(uint32_t aIndex) const 01085 { return GetVar(mDevice->point[aIndex]); }; 01086 01087 01089 double GetRange(uint32_t aIndex) const 01090 { return GetVar(mDevice->ranges[aIndex]); }; 01091 01093 double GetBearing(uint32_t aIndex) const 01094 { return GetVar(mDevice->scan[aIndex][1]); }; 01095 01096 01098 int GetIntensity(uint32_t aIndex) const 01099 { return GetVar(mDevice->intensity[aIndex]); }; 01100 01102 int GetID() const 01103 { return GetVar(mDevice->laser_id); }; 01104 01105 01114 void Configure(double aMinAngle, 01115 double aMaxAngle, 01116 uint32_t aScanRes, 01117 uint32_t aRangeRes, 01118 bool aIntensity, 01119 double aScanningFrequency); 01120 01123 void RequestConfigure(); 01124 01126 void RequestID(); 01127 01130 void RequestGeom(); 01131 01134 player_pose3d_t GetPose() 01135 { 01136 player_pose3d_t p; 01137 scoped_lock_t lock(mPc->mMutex); 01138 01139 p.px = mDevice->pose[0]; 01140 p.py = mDevice->pose[1]; 01141 p.pyaw = mDevice->pose[2]; 01142 return(p); 01143 } 01144 01147 player_pose3d_t GetRobotPose() 01148 { 01149 player_pose3d_t p; 01150 scoped_lock_t lock(mPc->mMutex); 01151 01152 p.px = mDevice->robot_pose[0]; 01153 p.py = mDevice->robot_pose[1]; 01154 p.pyaw = mDevice->robot_pose[2]; 01155 return(p); 01156 } 01157 01159 player_bbox3d_t GetSize() 01160 { 01161 player_bbox3d_t b; 01162 scoped_lock_t lock(mPc->mMutex); 01163 01164 b.sl = mDevice->size[0]; 01165 b.sw = mDevice->size[1]; 01166 return(b); 01167 } 01168 01170 double GetMinLeft() const 01171 { return GetVar(mDevice->min_left); }; 01172 01174 double GetMinRight() const 01175 { return GetVar(mDevice->min_right); }; 01176 01178 double MinLeft () const 01179 { return GetMinLeft(); } 01180 01182 double MinRight () const 01183 { return GetMinRight(); } 01184 01189 double operator [] (uint32_t index) const 01190 { return GetRange(index);} 01191 01192 }; 01193 01194 01199 class PLAYERCC_EXPORT LimbProxy : public ClientProxy 01200 { 01201 private: 01202 01203 void Subscribe(uint32_t aIndex); 01204 void Unsubscribe(); 01205 01206 // libplayerc data structure 01207 playerc_limb_t *mDevice; 01208 01209 public: 01210 01211 LimbProxy(PlayerClient *aPc, uint32_t aIndex=0); 01212 ~LimbProxy(); 01213 01216 void RequestGeometry(void); 01217 01219 void SetPowerConfig(bool aVal); 01221 void SetBrakesConfig(bool aVal); 01223 void SetSpeedConfig(float aSpeed); 01224 01226 void MoveHome(void); 01228 void Stop(void); 01230 void SetPose(float aPX, float aPY, float aPZ, 01231 float aAX, float aAY, float aAZ, 01232 float aOX, float aOY, float aOZ); 01234 void SetPosition(float aX, float aY, float aZ); 01237 void VectorMove(float aX, float aY, float aZ, float aLength); 01238 01240 player_limb_data_t GetData(void) const; 01242 player_limb_geom_req_t GetGeom(void) const; 01243 }; 01244 01245 01251 class PLAYERCC_EXPORT LinuxjoystickProxy : public ClientProxy 01252 { 01253 private: 01254 01255 void Subscribe(uint32_t aIndex); 01256 void Unsubscribe(); 01257 01258 // libplayerc data structure 01259 playerc_joystick_t *mDevice; 01260 01261 public: 01263 LinuxjoystickProxy(PlayerClient *aPc, uint32_t aIndex=0); 01265 ~LinuxjoystickProxy(); 01266 01268 uint32_t GetButtons() const { return GetVar(mDevice->buttons); }; 01269 01271 double GetAxes(uint32_t aIndex) const 01272 { if (GetVar(mDevice->axes_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->pos[aIndex]); }; 01275 double operator [] (uint32_t aIndex) const { return GetAxes(aIndex); } 01276 01278 uint32_t GetAxesCount() const { return GetVar(mDevice->axes_count); }; 01279 01281 // player_pose3d_t GetPose(uint32_t aIndex) const 01282 // { return GetVar(mDevice->poses[aIndex]); }; 01283 01284 // Enable/disable the joysticks. 01285 // Set @p state to 1 to enable, 0 to disable. 01286 // Note that when joysticks are disabled the client will still receive joystick 01287 // data, but the ranges will always be the last value read from the joysticks 01288 // before they were disabled. 01289 //void SetEnable(bool aEnable); 01290 01292 // void RequestGeom(); 01293 }; 01294 01295 01301 class PLAYERCC_EXPORT LocalizeProxy : public ClientProxy 01302 { 01303 01304 private: 01305 01306 void Subscribe(uint32_t aIndex); 01307 void Unsubscribe(); 01308 01309 // libplayerc data structure 01310 playerc_localize_t *mDevice; 01311 01312 public: 01313 01315 LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0); 01317 ~LocalizeProxy(); 01318 01320 // @todo should these be in a player_pose_t? 01321 uint32_t GetMapSizeX() const { return GetVar(mDevice->map_size_x); }; 01322 uint32_t GetMapSizeY() const { return GetVar(mDevice->map_size_y); }; 01323 01324 // @todo should these be in a player_pose_t? 01325 uint32_t GetMapTileX() const { return GetVar(mDevice->map_tile_x); }; 01326 uint32_t GetMapTileY() const { return GetVar(mDevice->map_tile_y); }; 01327 01329 double GetMapScale() const { return GetVar(mDevice->map_scale); }; 01330 01331 // Map data (empty = -1, unknown = 0, occupied = +1) 01332 // is this still needed? if so, 01333 //void GetMapCells(uint8_t* aCells) const 01334 //{ 01335 // return GetVarByRef(mDevice->map_cells, 01336 // mDevice->image+GetVar(mDevice->??map_cell_cout??), 01337 // aCells); 01338 //}; 01339 01341 uint32_t GetPendingCount() const { return GetVar(mDevice->pending_count); }; 01342 01344 uint32_t GetHypothCount() const { return GetVar(mDevice->hypoth_count); }; 01345 01347 player_localize_hypoth_t GetHypoth(uint32_t aIndex) const 01348 { return GetVar(mDevice->hypoths[aIndex]); }; 01349 01351 int GetParticles() 01352 { return playerc_localize_get_particles(mDevice); } 01353 01355 player_pose2d_t GetParticlePose(int index) const; 01356 01358 void SetPose(double pose[3], double cov[3]); 01359 01361 uint32_t GetNumHypoths() const { return GetVar(mDevice->hypoth_count); }; 01362 01365 uint32_t GetNumParticles() const { return GetVar(mDevice->num_particles); }; 01366 }; 01367 01368 01372 class PLAYERCC_EXPORT LogProxy : public ClientProxy 01373 { 01374 private: 01375 01376 void Subscribe(uint32_t aIndex); 01377 void Unsubscribe(); 01378 01379 // libplayerc data structure 01380 playerc_log_t *mDevice; 01381 01382 public: 01384 LogProxy(PlayerClient *aPc, uint32_t aIndex=0); 01385 01387 ~LogProxy(); 01388 01391 int GetType() const { return GetVar(mDevice->type); }; 01392 01394 int GetState() const { return GetVar(mDevice->state); }; 01395 01397 void QueryState(); 01398 01401 void SetState(int aState); 01402 01404 void SetWriteState(int aState); 01405 01407 void SetReadState(int aState); 01408 01410 void Rewind(); 01411 01413 void SetFilename(const std::string aFilename); 01414 }; 01415 01419 class PLAYERCC_EXPORT MapProxy : public ClientProxy 01420 { 01421 private: 01422 01423 void Subscribe(uint32_t aIndex); 01424 void Unsubscribe(); 01425 01426 // libplayerc data structure 01427 playerc_map_t *mDevice; 01428 01429 public: 01431 MapProxy(PlayerClient *aPc, uint32_t aIndex=0); 01432 01434 ~MapProxy(); 01435 01437 void RequestMap(); 01438 01440 int GetCellIndex(int x, int y) const 01441 { return y*GetWidth() + x; }; 01442 01444 int8_t GetCell(int x, int y) const 01445 { return GetVar(mDevice->cells[GetCellIndex(x,y)]); }; 01446 01448 double GetResolution() const { return GetVar(mDevice->resolution); }; 01449 01452 uint32_t GetWidth() const { return GetVar(mDevice->width); }; 01455 uint32_t GetHeight() const { return GetVar(mDevice->height); }; 01456 01457 double GetOriginX() const { return GetVar(mDevice->origin[0]); }; 01458 double GetOriginY() const { return GetVar(mDevice->origin[1]); }; 01459 01461 void GetMap(int8_t* aMap) const 01462 { 01463 return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->cells), 01464 reinterpret_cast<int8_t*>(mDevice->cells+GetWidth()*GetHeight()), 01465 aMap); 01466 }; 01467 }; 01468 01474 class PLAYERCC_EXPORT OpaqueProxy : public ClientProxy 01475 { 01476 01477 private: 01478 01479 void Subscribe(uint32_t aIndex); 01480 void Unsubscribe(); 01481 01482 // libplayerc data structure 01483 playerc_opaque_t *mDevice; 01484 01485 public: 01486 01488 OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0); 01490 ~OpaqueProxy(); 01491 01493 uint32_t GetCount() const { return GetVar(mDevice->data_count); }; 01494 01496 void GetData(uint8_t* aDest) const 01497 { 01498 return GetVarByRef(mDevice->data, 01499 mDevice->data+GetVar(mDevice->data_count), 01500 aDest); 01501 }; 01502 01504 void SendCmd(player_opaque_data_t* aData); 01505 01507 int SendReq(player_opaque_data_t* aRequest); 01508 01509 }; 01510 01514 class PLAYERCC_EXPORT PlannerProxy : public ClientProxy 01515 { 01516 01517 private: 01518 01519 void Subscribe(uint32_t aIndex); 01520 void Unsubscribe(); 01521 01522 // libplayerc data structure 01523 playerc_planner_t *mDevice; 01524 01525 public: 01526 01528 PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0); 01530 ~PlannerProxy(); 01531 01533 void SetGoalPose(double aGx, double aGy, double aGa); 01534 01537 void RequestWaypoints(); 01538 01541 void SetEnable(bool aEnable); 01542 01544 uint32_t GetPathValid() const { return GetVar(mDevice->path_valid); }; 01545 01547 uint32_t GetPathDone() const { return GetVar(mDevice->path_done); }; 01548 01551 double GetPx() const { return GetVar(mDevice->px); }; 01554 double GetPy() const { return GetVar(mDevice->py); }; 01557 double GetPa() const { return GetVar(mDevice->pa); }; 01558 01560 player_pose2d_t GetPose() const 01561 { 01562 player_pose2d_t p; 01563 scoped_lock_t lock(mPc->mMutex); 01564 p.px = mDevice->px; 01565 p.py = mDevice->py; 01566 p.pa = mDevice->pa; 01567 return(p); 01568 } 01569 01572 double GetGx() const { return GetVar(mDevice->gx); }; 01575 double GetGy() const { return GetVar(mDevice->gy); }; 01578 double GetGa() const { return GetVar(mDevice->ga); }; 01579 01581 player_pose2d_t GetGoal() const 01582 { 01583 player_pose2d_t p; 01584 scoped_lock_t lock(mPc->mMutex); 01585 p.px = mDevice->gx; 01586 p.py = mDevice->gy; 01587 p.pa = mDevice->ga; 01588 return(p); 01589 } 01590 01593 double GetWx() const { return GetVar(mDevice->wx); }; 01596 double GetWy() const { return GetVar(mDevice->wy); }; 01599 double GetWa() const { return GetVar(mDevice->wa); }; 01600 01602 player_pose2d_t GetCurrentWaypoint() const 01603 { 01604 player_pose2d_t p; 01605 scoped_lock_t lock(mPc->mMutex); 01606 p.px = mDevice->wx; 01607 p.py = mDevice->wy; 01608 p.pa = mDevice->wa; 01609 return(p); 01610 } 01611 01614 double GetIx(int i) const; 01617 double GetIy(int i) const; 01620 double GetIa(int i) const; 01621 01623 player_pose2d_t GetWaypoint(uint32_t aIndex) const 01624 { 01625 assert(aIndex < GetWaypointCount()); 01626 player_pose2d_t p; 01627 scoped_lock_t lock(mPc->mMutex); 01628 p.px = mDevice->waypoints[aIndex][0]; 01629 p.py = mDevice->waypoints[aIndex][1]; 01630 p.pa = mDevice->waypoints[aIndex][2]; 01631 return(p); 01632 } 01633 01637 int GetCurrentWaypointId() const 01638 { return GetVar(mDevice->curr_waypoint); }; 01639 01641 uint32_t GetWaypointCount() const 01642 { return GetVar(mDevice->waypoint_count); }; 01643 01648 player_pose2d_t operator [](uint32_t aIndex) const 01649 { return GetWaypoint(aIndex); } 01650 01651 }; 01652 01656 class PLAYERCC_EXPORT Pointcloud3dProxy : public ClientProxy 01657 { 01658 private: 01659 01660 void Subscribe(uint32_t aIndex); 01661 void Unsubscribe(); 01662 01663 // libplayerc data structure 01664 playerc_pointcloud3d_t *mDevice; 01665 01666 public: 01668 Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0); 01669 01671 ~Pointcloud3dProxy(); 01672 01674 uint32_t GetCount() const { return GetVar(mDevice->points_count); }; 01675 01677 player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const 01678 { return GetVar(mDevice->points[aIndex]); }; 01679 01682 player_pointcloud3d_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); } 01683 01684 }; 01685 01686 01691 class PLAYERCC_EXPORT Position1dProxy : public ClientProxy 01692 { 01693 01694 private: 01695 01696 void Subscribe(uint32_t aIndex); 01697 void Unsubscribe(); 01698 01699 // libplayerc data structure 01700 playerc_position1d_t *mDevice; 01701 01702 public: 01703 01705 Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0); 01707 ~Position1dProxy(); 01708 01712 void SetSpeed(double aVel); 01713 01717 void GoTo(double aPos, double aVel); 01718 01721 void RequestGeom(); 01722 01724 player_pose3d_t GetPose() const 01725 { 01726 player_pose3d_t p; 01727 scoped_lock_t lock(mPc->mMutex); 01728 p.px = mDevice->pose[0]; 01729 p.py = mDevice->pose[1]; 01730 p.pyaw = mDevice->pose[2]; 01731 return(p); 01732 } 01733 01735 player_bbox3d_t GetSize() const 01736 { 01737 player_bbox3d_t b; 01738 scoped_lock_t lock(mPc->mMutex); 01739 b.sl = mDevice->size[0]; 01740 b.sw = mDevice->size[1]; 01741 return(b); 01742 } 01743 01748 void SetMotorEnable(bool enable); 01749 01752 void SetOdometry(double aPos); 01753 01755 void ResetOdometry() { SetOdometry(0); }; 01756 01758 //void SetSpeedPID(double kp, double ki, double kd); 01759 01761 //void SetPositionPID(double kp, double ki, double kd); 01762 01765 //void SetPositionSpeedProfile(double spd, double acc); 01766 01768 double GetPos() const { return GetVar(mDevice->pos); }; 01769 01771 double GetVel() const { return GetVar(mDevice->vel); }; 01772 01774 bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; }; 01775 01777 uint8_t GetStatus() const { return GetVar(mDevice->status); }; 01778 01780 bool IsLimitMin() const 01781 { return (GetVar(mDevice->status) & 01782 (1 << PLAYER_POSITION1D_STATUS_LIMIT_MIN)) > 0; }; 01783 01785 bool IsLimitCen() const 01786 { return (GetVar(mDevice->status) & 01787 (1 << PLAYER_POSITION1D_STATUS_LIMIT_CEN)) > 0; }; 01788 01790 bool IsLimitMax() const 01791 { return (GetVar(mDevice->status) & 01792 (1 << PLAYER_POSITION1D_STATUS_LIMIT_MAX)) > 0; }; 01793 01795 bool IsOverCurrent() const 01796 { return (GetVar(mDevice->status) & 01797 (1 << PLAYER_POSITION1D_STATUS_OC)) > 0; }; 01798 01800 bool IsTrajComplete() const 01801 { return (GetVar(mDevice->status) & 01802 (1 << PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE)) > 0; }; 01803 01805 bool IsEnabled() const 01806 { return (GetVar(mDevice->status) & 01807 (1 << PLAYER_POSITION1D_STATUS_ENABLED)) > 0; }; 01808 01809 }; 01810 01815 class PLAYERCC_EXPORT Position2dProxy : public ClientProxy 01816 { 01817 01818 private: 01819 01820 void Subscribe(uint32_t aIndex); 01821 void Unsubscribe(); 01822 01823 // libplayerc data structure 01824 playerc_position2d_t *mDevice; 01825 01826 public: 01827 01829 Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0); 01831 ~Position2dProxy(); 01832 01836 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed); 01837 01840 void SetSpeed(double aXSpeed, double aYawSpeed) 01841 { return SetSpeed(aXSpeed, 0, aYawSpeed);} 01842 01844 void SetSpeed(player_pose2d_t vel) 01845 { return SetSpeed(vel.px, vel.py, vel.pa);} 01846 01850 void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead); 01851 01854 void SetVelHead(double aXSpeed, double aYawHead) 01855 { return SetVelHead(aXSpeed, 0, aYawHead);} 01856 01857 01861 void GoTo(player_pose2d_t pos, player_pose2d_t vel); 01862 01864 void GoTo(player_pose2d_t pos) 01865 { player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); } 01866 01869 void GoTo(double aX, double aY, double aYaw) 01870 { player_pose2d_t pos = {aX,aY,aYaw}; player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); } 01871 01873 void SetCarlike(double aXSpeed, double aDriveAngle); 01874 01877 void RequestGeom(); 01878 01880 // body (fill it in by calling RequestGeom()). 01881 player_pose3d_t GetOffset() 01882 { 01883 player_pose3d_t p; 01884 scoped_lock_t lock(mPc->mMutex); 01885 p.px = mDevice->pose[0]; 01886 p.py = mDevice->pose[1]; 01887 p.pyaw = mDevice->pose[2]; 01888 return(p); 01889 } 01890 01892 player_bbox3d_t GetSize() 01893 { 01894 player_bbox3d_t b; 01895 scoped_lock_t lock(mPc->mMutex); 01896 b.sl = mDevice->size[0]; 01897 b.sw = mDevice->size[1]; 01898 return(b); 01899 } 01900 01905 void SetMotorEnable(bool enable); 01906 01907 // Select velocity control mode. 01908 // 01909 // For the the p2os_position driver, set @p mode to 0 for direct wheel 01910 // velocity control (default), or 1 for separate translational and 01911 // rotational control. 01912 // 01913 // For the reb_position driver: 0 is direct velocity control, 1 is for 01914 // velocity-based heading PD controller (uses DoDesiredHeading()). 01915 //void SelectVelocityControl(unsigned char mode); 01916 01918 void ResetOdometry(); 01919 01922 //void SelectPositionMode(unsigned char mode); 01923 01926 void SetOdometry(double aX, double aY, double aYaw); 01927 01929 //void SetSpeedPID(double kp, double ki, double kd); 01930 01932 //void SetPositionPID(double kp, double ki, double kd); 01933 01936 //void SetPositionSpeedProfile(double spd, double acc); 01937 01938 // 01939 // void DoStraightLine(double m); 01940 01941 // 01942 //void DoRotation(double yawspeed); 01943 01944 // 01945 //void DoDesiredHeading(double yaw, double xspeed, double yawspeed); 01946 01947 // 01948 //void SetStatus(uint8_t cmd, uint16_t value); 01949 01950 // 01951 //void PlatformShutdown(); 01952 01954 double GetXPos() const { return GetVar(mDevice->px); }; 01955 01957 double GetYPos() const { return GetVar(mDevice->py); }; 01958 01960 double GetYaw() const { return GetVar(mDevice->pa); }; 01961 01963 double GetXSpeed() const { return GetVar(mDevice->vx); }; 01964 01966 double GetYSpeed() const { return GetVar(mDevice->vy); }; 01967 01969 double GetYawSpeed() const { return GetVar(mDevice->va); }; 01970 01972 bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; }; 01973 01974 }; 01975 01982 class PLAYERCC_EXPORT Position3dProxy : public ClientProxy 01983 { 01984 01985 private: 01986 01987 void Subscribe(uint32_t aIndex); 01988 void Unsubscribe(); 01989 01990 // libplayerc data structure 01991 playerc_position3d_t *mDevice; 01992 01993 public: 01994 01996 Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0); 01998 ~Position3dProxy(); 01999 02003 void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed, 02004 double aRollSpeed, double aPitchSpeed, double aYawSpeed); 02005 02009 void SetSpeed(double aXSpeed, double aYSpeed, 02010 double aZSpeed, double aYawSpeed) 02011 { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); } 02012 02014 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed) 02015 { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); } 02016 02019 void SetSpeed(double aXSpeed, double aYawSpeed) 02020 { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);} 02021 02023 void SetSpeed(player_pose3d_t vel) 02024 { SetSpeed(vel.px,vel.py,vel.pz,vel.proll,vel.ppitch,vel.pyaw);} 02025 02029 void GoTo(player_pose3d_t aPos, player_pose3d_t aVel); 02030 02032 void GoTo(player_pose3d_t aPos) 02033 { player_pose3d_t vel = {0,0,0,0,0,0}; GoTo(aPos, vel); } 02034 02035 02038 void GoTo(double aX, double aY, double aZ, 02039 double aRoll, double aPitch, double aYaw) 02040 { player_pose3d_t pos = {aX,aY,aZ,aRoll,aPitch,aYaw}; 02041 player_pose3d_t vel = {0,0,0,0,0,0}; 02042 GoTo(pos, vel); 02043 } 02044 02049 void SetMotorEnable(bool aEnable); 02050 02053 void SelectVelocityControl(int aMode); 02054 02056 void ResetOdometry(); 02057 02061 void SetOdometry(double aX, double aY, double aZ, 02062 double aRoll, double aPitch, double aYaw); 02063 02066 void RequestGeom(); 02067 02068 // Select position mode 02069 // Set @p mode for 0 for velocity mode, 1 for position mode. 02070 //void SelectPositionMode(unsigned char mode); 02071 02072 // 02073 //void SetSpeedPID(double kp, double ki, double kd); 02074 02075 // 02076 //void SetPositionPID(double kp, double ki, double kd); 02077 02078 // Sets the ramp profile for position based control 02079 // spd rad/s, acc rad/s/s 02080 //void SetPositionSpeedProfile(double spd, double acc); 02081 02083 double GetXPos() const { return GetVar(mDevice->pos_x); }; 02084 02086 double GetYPos() const { return GetVar(mDevice->pos_y); }; 02087 02089 double GetZPos() const { return GetVar(mDevice->pos_z); }; 02090 02092 double GetRoll() const { return GetVar(mDevice->pos_roll); }; 02093 02095 double GetPitch() const { return GetVar(mDevice->pos_pitch); }; 02096 02098 double GetYaw() const { return GetVar(mDevice->pos_yaw); }; 02099 02101 double GetXSpeed() const { return GetVar(mDevice->vel_x); }; 02102 02104 double GetYSpeed() const { return GetVar(mDevice->vel_y); }; 02105 02107 double GetZSpeed() const { return GetVar(mDevice->vel_z); }; 02108 02110 double GetRollSpeed() const { return GetVar(mDevice->vel_roll); }; 02111 02113 double GetPitchSpeed() const { return GetVar(mDevice->vel_pitch); }; 02114 02116 double GetYawSpeed() const { return GetVar(mDevice->vel_yaw); }; 02117 02119 bool GetStall () const { return GetVar(mDevice->stall) != 0 ? true : false; }; 02120 }; 02123 class PLAYERCC_EXPORT PowerProxy : public ClientProxy 02124 { 02125 private: 02126 02127 void Subscribe(uint32_t aIndex); 02128 void Unsubscribe(); 02129 02130 // libplayerc data structure 02131 playerc_power_t *mDevice; 02132 02133 public: 02135 PowerProxy(PlayerClient *aPc, uint32_t aIndex=0); 02137 ~PowerProxy(); 02138 02140 double GetCharge() const { return GetVar(mDevice->charge); }; 02141 02143 double GetPercent() const {return GetVar(mDevice->percent); }; 02144 02146 double GetJoules() const {return GetVar(mDevice->joules); }; 02147 02149 double GetWatts() const {return GetVar(mDevice->watts); }; 02150 02152 bool GetCharging() const {return GetVar(mDevice->charging) != 0 ? true : false;}; 02153 02154 // Return whether the power data is valid 02155 bool IsValid() const {return GetVar(mDevice->valid) != 0 ? true : false;}; 02156 }; 02157 02164 class PLAYERCC_EXPORT PtzProxy : public ClientProxy 02165 { 02166 02167 private: 02168 02169 void Subscribe(uint32_t aIndex); 02170 void Unsubscribe(); 02171 02172 // libplayerc data structure 02173 playerc_ptz_t *mDevice; 02174 02175 public: 02177 PtzProxy(PlayerClient *aPc, uint32_t aIndex=0); 02178 // destructor 02179 ~PtzProxy(); 02180 02181 public: 02182 02186 void SetCam(double aPan, double aTilt, double aZoom); 02187 02189 void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0); 02190 02193 void SelectControlMode(uint32_t aMode); 02194 02196 double GetPan() const { return GetVar(mDevice->pan); }; 02198 double GetTilt() const { return GetVar(mDevice->tilt); }; 02200 double GetZoom() const { return GetVar(mDevice->zoom); }; 02201 02203 int GetStatus(); 02204 02205 02206 }; 02207 02210 class PLAYERCC_EXPORT RangerProxy : public ClientProxy 02211 { 02212 private: 02213 02214 void Subscribe(uint32_t aIndex); 02215 void Unsubscribe(); 02216 02217 // libplayerc data structure 02218 playerc_ranger_t *mDevice; 02219 02220 public: 02222 RangerProxy(PlayerClient *aPc, uint32_t aIndex=0); 02224 ~RangerProxy(); 02225 02227 uint32_t GetElementCount() const { return GetVar(mDevice->element_count); }; 02228 02230 player_pose3d_t GetDevicePose() const { return GetVar(mDevice->device_pose); }; 02232 player_bbox3d_t GetDeviceSize() const { return GetVar(mDevice->device_size); }; 02233 02235 player_pose3d_t GetElementPose(uint32_t aIndex) const; 02237 player_bbox3d_t GetElementSize(uint32_t aIndex) const; 02238 02240 uint32_t GetRangeCount() const { return GetVar(mDevice->ranges_count); }; 02242 double GetRange(uint32_t aIndex) const; 02244 double operator[] (uint32_t aIndex) const { return GetRange(aIndex); } 02245 02247 uint32_t GetIntensityCount() const { return GetVar(mDevice->intensities_count); } ; 02249 double GetIntensity(uint32_t aIndex) const; 02250 02253 void SetPower(bool aEnable); 02254 02257 void SetIntensityData(bool aEnable); 02258 02260 void RequestGeom(); 02261 02266 void Configure(double aMinAngle, 02267 double aMaxAngle, 02268 double aAngularRes, 02269 double aMinRange, 02270 double aMaxRange, 02271 double aRangeRes, 02272 double aFrequency); 02273 02276 void RequestConfigure(); 02277 02279 double GetMinAngle() const { return GetVar(mDevice->min_angle); }; 02280 02282 double GetMaxAngle() const { return GetVar(mDevice->max_angle); }; 02283 02285 double GetAngularRes() const { return GetVar(mDevice->angular_res); }; 02286 02288 double GetMinRange() const { return GetVar(mDevice->min_range); }; 02289 02291 double GetMaxRange() const { return GetVar(mDevice->max_range); }; 02292 02294 double GetRangeRes() const { return GetVar(mDevice->range_res); }; 02295 02297 double GetFrequency() const { return GetVar(mDevice->frequency); }; 02298 }; 02299 02302 class PLAYERCC_EXPORT RFIDProxy : public ClientProxy 02303 { 02304 02305 private: 02306 02307 void Subscribe(uint32_t aIndex); 02308 void Unsubscribe(); 02309 02310 // libplayerc data structure 02311 playerc_rfid_t *mDevice; 02312 02313 public: 02315 RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0); 02317 ~RFIDProxy(); 02318 02320 uint32_t GetTagsCount() const { return GetVar(mDevice->tags_count); }; 02322 playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const 02323 { return GetVar(mDevice->tags[aIndex]);}; 02324 02329 playerc_rfidtag_t operator [](uint32_t aIndex) const 02330 { return(GetRFIDTag(aIndex)); } 02331 }; 02332 02337 class PLAYERCC_EXPORT SimulationProxy : public ClientProxy 02338 { 02339 private: 02340 02341 void Subscribe(uint32_t aIndex); 02342 void Unsubscribe(); 02343 02344 // libplayerc data structure 02345 playerc_simulation_t *mDevice; 02346 02347 public: 02349 SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0); 02351 ~SimulationProxy(); 02352 02355 void SetPose2d(char* identifier, double x, double y, double a); 02356 02359 void GetPose2d(char* identifier, double& x, double& y, double& a); 02360 02363 void SetPose3d(char* identifier, double x, double y, double z, 02364 double roll, double pitch, double yaw); 02365 02368 void GetPose3d(char* identifier, double& x, double& y, double& z, 02369 double& roll, double& pitch, double& yaw, double& time); 02370 02372 void GetProperty(char* identifier, char *name, void *value, size_t value_len ); 02373 02375 void SetProperty(char* identifier, char *name, void *value, size_t value_len ); 02376 }; 02377 02378 02384 class PLAYERCC_EXPORT SonarProxy : public ClientProxy 02385 { 02386 private: 02387 02388 void Subscribe(uint32_t aIndex); 02389 void Unsubscribe(); 02390 02391 // libplayerc data structure 02392 playerc_sonar_t *mDevice; 02393 02394 public: 02396 SonarProxy(PlayerClient *aPc, uint32_t aIndex=0); 02398 ~SonarProxy(); 02399 02401 uint32_t GetCount() const { return GetVar(mDevice->scan_count); }; 02402 02404 double GetScan(uint32_t aIndex) const 02405 { if (GetVar(mDevice->scan_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->scan[aIndex]); }; 02408 double operator [] (uint32_t aIndex) const { return GetScan(aIndex); } 02409 02411 uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); }; 02412 02414 player_pose3d_t GetPose(uint32_t aIndex) const 02415 { return GetVar(mDevice->poses[aIndex]); }; 02416 02417 // Enable/disable the sonars. 02418 // Set @p state to 1 to enable, 0 to disable. 02419 // Note that when sonars are disabled the client will still receive sonar 02420 // data, but the ranges will always be the last value read from the sonars 02421 // before they were disabled. 02422 //void SetEnable(bool aEnable); 02423 02425 void RequestGeom(); 02426 }; 02427 02432 class PLAYERCC_EXPORT SpeechProxy : public ClientProxy 02433 { 02434 02435 private: 02436 02437 void Subscribe(uint32_t aIndex); 02438 void Unsubscribe(); 02439 02440 // libplayerc data structure 02441 playerc_speech_t *mDevice; 02442 02443 public: 02445 SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0); 02447 ~SpeechProxy(); 02448 02451 void Say(std::string aStr); 02452 }; 02453 02457 class PLAYERCC_EXPORT SpeechRecognitionProxy : public ClientProxy 02458 { 02459 void Subscribe(uint32_t aIndex); 02460 void Unsubscribe(); 02461 02463 playerc_speechrecognition_t *mDevice; 02464 public: 02466 SpeechRecognitionProxy(PlayerClient *aPc, uint32_t aIndex=0); 02467 ~SpeechRecognitionProxy(); 02469 std::string GetWord(uint32_t aWord) const{ 02470 scoped_lock_t lock(mPc->mMutex); 02471 return std::string(mDevice->words[aWord]); 02472 } 02473 02475 uint32_t GetCount(void) const { return GetVar(mDevice->wordCount); } 02476 02479 std::string operator [](uint32_t aWord) { return(GetWord(aWord)); } 02480 }; 02481 02485 class PLAYERCC_EXPORT VectorMapProxy : public ClientProxy 02486 { 02487 02488 private: 02489 02490 // Subscribe 02491 void Subscribe(uint32_t aIndex); 02492 // Unsubscribe 02493 void Unsubscribe(); 02494 02495 // libplayerc data structure 02496 playerc_vectormap_t *mDevice; 02497 02498 bool map_info_cached; 02499 public: 02500 // Constructor 02501 VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0); 02502 // Destructor 02503 ~VectorMapProxy(); 02504 02505 void GetMapInfo(); 02506 void GetLayerData(unsigned layer_index); 02507 02508 int GetLayerCount() const; 02509 std::vector<std::string> GetLayerNames() const; 02510 int GetFeatureCount(unsigned layer_index) const; 02511 const uint8_t * GetFeatureData(unsigned layer_index, unsigned feature_index) const; 02512 size_t GetFeatureDataCount(unsigned layer_index, unsigned feature_index) const; 02513 }; 02514 02517 class PLAYERCC_EXPORT WiFiProxy: public ClientProxy 02518 { 02519 02520 private: 02521 02522 void Subscribe(uint32_t aIndex); 02523 void Unsubscribe(); 02524 02525 // libplayerc data structure 02526 playerc_wifi_t *mDevice; 02527 02528 public: 02530 WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0); 02532 ~WiFiProxy(); 02533 02534 const playerc_wifi_link_t *GetLink(int aLink); 02535 02536 int GetLinkCount() const { return mDevice->link_count; }; 02537 char* GetOwnIP() const { return mDevice->ip; }; 02538 02539 char* GetLinkIP(int index) const { return (char*) mDevice->links[index].ip; }; 02540 char* GetLinkMAC(int index) const { return (char*) mDevice->links[index].mac; }; 02541 char* GetLinkESSID(int index) const { return (char*)mDevice->links[index].essid; }; 02542 double GetLinkFreq(int index) const {return mDevice->links[index].freq;}; 02543 int GetLinkMode(int index) const { return mDevice->links[index].mode; }; 02544 int GetLinkEncrypt(int index) const {return mDevice->links[index].encrypt; }; 02545 int GetLinkQuality(int index) const { return mDevice->links[index].qual; }; 02546 int GetLinkLevel(int index) const {return mDevice->links[index].level; }; 02547 int GetLinkNoise(int index) const {return mDevice->links[index].noise; } ; 02548 02549 //player_wifi_link_t 02550 // int GetLinkQuality(char/// ip = NULL); 02551 // int GetLevel(char/// ip = NULL); 02552 // int GetLeveldBm(char/// ip = NULL) { return GetLevel(ip) - 0x100; } 02553 // int GetNoise(char/// ip = NULL); 02554 // int GetNoisedBm(char/// ip = NULL) { return GetNoise(ip) - 0x100; } 02555 // 02556 // uint16_t GetMaxLinkQuality() { return maxqual; } 02557 // uint8_t GetMode() { return op_mode; } 02558 // 02559 // int GetBitrate(); 02560 // 02561 // char/// GetMAC(char *buf, int len); 02562 // 02563 // char/// GetIP(char *buf, int len); 02564 // char/// GetAP(char *buf, int len); 02565 // 02566 // int AddSpyHost(char *address); 02567 // int RemoveSpyHost(char *address); 02568 // 02569 // private: 02570 // int GetLinkIndex(char *ip); 02571 // 02572 // /// The current wifi data. 02573 // int link_count; 02574 // player_wifi_link_t links[PLAYER_WIFI_MAX_LINKS]; 02575 // uint32_t throughput; 02576 // uint8_t op_mode; 02577 // int32_t bitrate; 02578 // uint16_t qual_type, maxqual, maxlevel, maxnoise; 02579 // 02580 // char access_point[32]; 02581 }; 02582 02585 class PLAYERCC_EXPORT WSNProxy : public ClientProxy 02586 { 02587 02588 private: 02589 02590 void Subscribe(uint32_t aIndex); 02591 void Unsubscribe(); 02592 02593 // libplayerc data structure 02594 playerc_wsn_t *mDevice; 02595 02596 public: 02598 WSNProxy(PlayerClient *aPc, uint32_t aIndex=0); 02600 ~WSNProxy(); 02601 02602 uint32_t GetNodeType () const { return GetVar(mDevice->node_type); }; 02603 uint32_t GetNodeID () const { return GetVar(mDevice->node_id); }; 02604 uint32_t GetNodeParentID() const { return GetVar(mDevice->node_parent_id); }; 02605 02606 player_wsn_node_data_t 02607 GetNodeDataPacket() const { return GetVar(mDevice->data_packet); }; 02608 02609 void SetDevState(int nodeID, int groupID, int devNr, int value); 02610 void Power(int nodeID, int groupID, int value); 02611 void DataType(int value); 02612 void DataFreq(int nodeID, int groupID, float frequency); 02613 }; 02614 02616 } 02617 02618 namespace std 02619 { 02620 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_point_2d_t& c); 02621 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose2d_t& c); 02622 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose3d_t& c); 02623 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox2d_t& c); 02624 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox3d_t& c); 02625 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_segment_t& c); 02626 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_extent2d_t& c); 02627 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const playerc_device_info_t& c); 02628 02629 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ClientProxy& c); 02630 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ActArrayProxy& c); 02631 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AioProxy& c); 02632 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AudioProxy& a); 02633 //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlinkenLightProxy& c); 02634 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlobfinderProxy& c); 02635 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BumperProxy& c); 02636 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::CameraProxy& c); 02637 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::DioProxy& c); 02638 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::FiducialProxy& c); 02639 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GpsProxy& c); 02640 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GripperProxy& c); 02641 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ImuProxy& c); 02642 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::IrProxy& c); 02643 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LaserProxy& c); 02644 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LimbProxy& c); 02645 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LinuxjoystickProxy& c); 02646 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LocalizeProxy& c); 02647 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LogProxy& c); 02648 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::MapProxy& c); 02649 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::OpaqueProxy& c); 02650 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PlannerProxy& c); 02651 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position1dProxy& c); 02652 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position2dProxy& c); 02653 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position3dProxy& c); 02654 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PowerProxy& c); 02655 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PtzProxy& c); 02656 PLAYERCC_EXPORT std::ostream& operator << (std::ostream &os, const PlayerCc::RangerProxy &c); 02657 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SimulationProxy& c); 02658 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SonarProxy& c); 02659 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechProxy& c); 02660 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechRecognitionProxy& c); 02661 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::VectorMapProxy& c); 02662 //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WafeformProxy& c); 02663 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WiFiProxy& c); 02664 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::RFIDProxy& c); 02665 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WSNProxy& c); 02666 } 02667 02668 #endif 02669