playerc++.h
1 /*
2  * Player - One Hell of a Robot Server
3  * Copyright (C) 2000-2003
4  * Brian Gerkey, Kasper Stoy, Richard Vaughan, & Andrew Howard
5  *
6  *
7  * This program is free software; you can redistribute it and/or modify
8  * it under the terms of the GNU General Public License as published by
9  * the Free Software Foundation; either version 2 of the License, or
10  * (at your option) any later version.
11  *
12  * This program is distributed in the hope that it will be useful,
13  * but WITHOUT ANY WARRANTY; without even the implied warranty of
14  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15  * GNU General Public License for more details.
16  *
17  * You should have received a copy of the GNU General Public License
18  * along with this program; if not, write to the Free Software
19  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
20  *
21  */
22 /********************************************************************
23  *
24  * This library is free software; you can redistribute it and/or
25  * modify it under the terms of the GNU Lesser General Public
26  * License as published by the Free Software Foundation; either
27  * version 2.1 of the License, or (at your option) any later version.
28  *
29  * This library is distributed in the hope that it will be useful,
30  * but WITHOUT ANY WARRANTY; without even the implied warranty of
31  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU
32  * Lesser General Public License for more details.
33  *
34  * You should have received a copy of the GNU Lesser General Public
35  * License along with this library; if not, write to the Free Software
36  * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA
37  *
38  ********************************************************************/
39 
40 /***************************************************************************
41  * Desc: Player v2.0 C++ client
42  * Authors: Brad Kratochvil, Toby Collett
43  *
44  * Date: 23 Sep 2005
45  # CVS: $Id: playerc++.h 8173 2009-08-04 07:25:00Z gbiggs $
46  **************************************************************************/
47 
48 
49 #ifndef PLAYERCC_H
50 #define PLAYERCC_H
51 
52 #include <cstddef>
53 #include <cmath>
54 #include <string>
55 #include <list>
56 #include <vector>
57 #include <cstring>
58 
59 #include "libplayerc/playerc.h"
60 #include "libplayerc++/utility.h"
61 #include "libplayerc++/playerclient.h"
62 #include "libplayerc++/playererror.h"
63 #include "libplayerc++/clientproxy.h"
64 #include "libplayerinterface/interface_util.h"
65 
66 #if defined (WIN32)
67  #if defined (PLAYER_STATIC)
68  #define PLAYERCC_EXPORT
69  #elif defined (playerc___EXPORTS)
70  #define PLAYERCC_EXPORT __declspec (dllexport)
71  #else
72  #define PLAYERCC_EXPORT __declspec (dllimport)
73  #endif
74 #else
75  #define PLAYERCC_EXPORT
76 #endif
77 
78 // Don't think we need to include these here
79 /*
80 #ifdef HAVE_BOOST_SIGNALS
81  #include <boost/signal.hpp>
82  #include <boost/bind.hpp>
83 #endif
84 
85 #ifdef HAVE_BOOST_THREAD
86  #include <boost/thread/mutex.hpp>
87  #include <boost/thread/thread.hpp>
88  #include <boost/thread/xtime.hpp>
89 #endif
90 */
91 
92 namespace PlayerCc
93 {
94 
95 // /**
96 // * The @p SomethingProxy class is a template for adding new subclasses of
97 // * ClientProxy. You need to have at least all of the following:
98 // */
99 // class SomethingProxy : public ClientProxy
100 // {
101 //
102 // private:
103 //
104 // // Subscribe
105 // void Subscribe(uint32_t aIndex);
106 // // Unsubscribe
107 // void Unsubscribe();
108 //
109 // // libplayerc data structure
110 // playerc_something_t *mDevice;
111 //
112 // public:
113 // // Constructor
114 // SomethingProxy(PlayerClient *aPc, uint32_t aIndex=0);
115 // // Destructor
116 // ~SomethingProxy();
117 //
118 // };
119 
131 // ==============================================================
132 //
133 // These are alphabetized, please keep them that way!!!
134 //
135 // ==============================================================
136 
141 class PLAYERCC_EXPORT ActArrayProxy : public ClientProxy
142 {
143  private:
144 
145  void Subscribe(uint32_t aIndex);
146  void Unsubscribe();
147 
148  // libplayerc data structure
149  playerc_actarray_t *mDevice;
150 
151  public:
152 
154  ActArrayProxy(PlayerClient *aPc, uint32_t aIndex=0);
156  ~ActArrayProxy();
157 
160  void RequestGeometry(void);
161 
163  void SetPowerConfig(bool aVal);
165  void SetBrakesConfig(bool aVal);
167  void SetSpeedConfig(uint32_t aJoint, float aSpeed);
168 
170  void MoveTo(uint32_t aJoint, float aPos);
172  void MoveToMulti(std::vector<float> aPos);
174  void MoveAtSpeed(uint32_t aJoint, float aSpeed);
176  void MoveAtSpeedMulti(std::vector<float> aSpeed);
178  void MoveHome(int aJoint);
180  void SetActuatorCurrent(uint32_t aJoint, float aCurrent);
182  void SetActuatorCurrentMulti(std::vector<float> aCurrent);
183 
185  uint32_t GetCount(void) const { return GetVar(mDevice->actuators_count); }
187  player_actarray_actuator_t GetActuatorData(uint32_t aJoint) const;
189  player_actarray_actuatorgeom_t GetActuatorGeom(uint32_t aJoint) const;
191  player_point_3d_t GetBasePos(void) const { return GetVar(mDevice->base_pos); }
193  player_orientation_3d_t GetBaseOrientation(void) const { return GetVar(mDevice->base_orientation); }
194 
195 
200  player_actarray_actuator_t operator [](uint32_t aJoint)
201  { return(GetActuatorData(aJoint)); }
202 };
203 
207 class PLAYERCC_EXPORT AioProxy : public ClientProxy
208 {
209  private:
210 
211  void Subscribe(uint32_t aIndex);
212  void Unsubscribe();
213 
214  // libplayerc data structure
215  playerc_aio_t *mDevice;
216 
217  public:
218 
219  AioProxy (PlayerClient *aPc, uint32_t aIndex=0);
220  ~AioProxy();
221 
223  uint32_t GetCount() const { return(GetVar(mDevice->voltages_count)); };
224 
226  double GetVoltage(uint32_t aIndex) const
227  { return(GetVar(mDevice->voltages[aIndex])); };
228 
230  void SetVoltage(uint32_t aIndex, double aVoltage);
231 
236  double operator [](uint32_t aIndex) const
237  { return GetVoltage(aIndex); }
238 
239 };
240 
241 
245 class PLAYERCC_EXPORT AudioProxy : public ClientProxy
246 {
247 
248  private:
249 
250  void Subscribe(uint32_t aIndex);
251  void Unsubscribe();
252 
253  // libplayerc data structure
254  playerc_audio_t *mDevice;
255 
256  public:
257 
258  AudioProxy(PlayerClient *aPc, uint32_t aIndex=0);
259  ~AudioProxy();
260 
262  uint32_t GetMixerDetailsCount() const {return(GetVar(mDevice->channel_details_list.details_count));};
264  player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const {return(GetVar(mDevice->channel_details_list.details[aIndex]));};
266  uint32_t GetDefaultOutputChannel() const {return(GetVar(mDevice->channel_details_list.default_output));};
268  uint32_t GetDefaultInputChannel() const {return(GetVar(mDevice->channel_details_list.default_input));};
269 
271  uint32_t GetWavDataLength() const {return(GetVar(mDevice->wav_data.data_count));};
276  void GetWavData(uint8_t* aData) const
277  {
278  return GetVarByRef(mDevice->wav_data.data,
279  mDevice->wav_data.data+GetWavDataLength(),
280  aData);
281  };
282 
284  uint32_t GetSeqCount() const {return(GetVar(mDevice->seq_data.tones_count));};
286  player_audio_seq_item_t GetSeqItem(int aIndex) const {return(GetVar(mDevice->seq_data.tones[aIndex]));};
287 
289  uint32_t GetChannelCount() const {return(GetVar(mDevice->mixer_data.channels_count));};
291  player_audio_mixer_channel_t GetChannel(int aIndex) const {return(GetVar(mDevice->mixer_data.channels[aIndex]));};
293  uint32_t GetState(void) const {return(GetVar(mDevice->state));};
294 
295 
296 
298  void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
299 
301  void SetWavStremRec(bool aState);
302 
304  void PlaySample(int aIndex);
305 
307  void PlaySeq(player_audio_seq_t * aTones);
308 
310  void SetMultMixerLevels(player_audio_mixer_channel_list_t * aLevels);
311 
313  void SetMixerLevel(uint32_t index, float amplitude, uint8_t active);
314 
317  void RecordWav();
318 
320  void LoadSample(int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
321 
324  void GetSample(int aIndex);
325 
327  void RecordSample(int aIndex, uint32_t aLength);
328 
331  void GetMixerLevels();
332 
335  void GetMixerDetails();
336 
337 };
338 
346 class PLAYERCC_EXPORT BlackBoardProxy : public ClientProxy
347 {
348  private:
349  void Subscribe(uint32_t aIndex);
350  void Unsubscribe();
351 
352  // libplayerc data structure
353  playerc_blackboard_t *mDevice;
354 
355  public:
357  BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0);
359  ~BlackBoardProxy();
361  player_blackboard_entry_t *SubscribeToKey(const char *key, const char* group = "");
363  void UnsubscribeFromKey(const char *key, const char* group = "");
365  void SubscribeToGroup(const char* key);
367  void UnsubscribeFromGroup(const char* group);
369  void SetEntry(const player_blackboard_entry_t &entry);
371  player_blackboard_entry_t *GetEntry(const char* key, const char* group);
373  void SetEventHandler(void (*on_blackboard_event)(playerc_blackboard_t *, player_blackboard_entry_t));
374 };
375 
376 // /**
377 // The @p BlinkenlightProxy class is used to enable and disable
378 // a flashing indicator light, and to set its period, via a @ref
379 // interface_blinkenlight device */
380 // class PLAYERCC_EXPORT BlinkenLightProxy : public ClientProxy
381 // {
382 // private:
383 //
384 // void Subscribe(uint32_t aIndex);
385 // void Unsubscribe();
386 //
387 // // libplayerc data structure
388 // playerc_blinkenlight_t *mDevice;
389 //
390 // public:
391 // /** Constructor.
392 // Leave the access field empty to start unconnected.
393 // */
394 // BlinkenLightProxy(PlayerClient *aPc, uint32_t aIndex=0);
395 // ~BlinkenLightProxy();
396 //
397 // // true: indicator light enabled, false: disabled.
398 // bool GetEnable();
399 //
400 // /** The current period (one whole on/off cycle) of the blinking
401 // light. If the period is zero and the light is enabled, the light
402 // is on.
403 // */
404 // void SetPeriod(double aPeriod);
405 //
406 // /** Set the state of the indicator light. A period of zero means
407 // the light will be unblinkingly on or off. Returns 0 on
408 // success, else -1.
409 // */
410 // void SetEnable(bool aSet);
411 // };
412 
419 class PLAYERCC_EXPORT BlobfinderProxy : public ClientProxy
420 {
421  private:
422 
423  void Subscribe(uint32_t aIndex);
424  void Unsubscribe();
425 
426  // libplayerc data structure
427  playerc_blobfinder_t *mDevice;
428 
429  public:
431  BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0);
433  ~BlobfinderProxy();
434 
436  uint32_t GetCount() const { return GetVar(mDevice->blobs_count); };
438  playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
439  { return GetVar(mDevice->blobs[aIndex]);};
440 
442  uint32_t GetWidth() const { return GetVar(mDevice->width); };
444  uint32_t GetHeight() const { return GetVar(mDevice->height); };
445 
450  playerc_blobfinder_blob_t operator [](uint32_t aIndex) const
451  { return(GetBlob(aIndex)); }
452 
453 /*
455  void SetTrackingColor(uint32_t aReMin=0, uint32_t aReMax=255, uint32_t aGrMin=0,
456  uint32_t aGrMax=255, uint32_t aBlMin=0, uint32_t aBlMax=255);
457  void SetImagerParams(int aContrast, int aBrightness,
458  int aAutogain, int aColormode);
459  void SetContrast(int aC);
460  void SetColorMode(int aM);
461  void SetBrightness(int aB);
462  void SetAutoGain(int aG);*/
463 
464 };
465 
470 class PLAYERCC_EXPORT BumperProxy : public ClientProxy
471 {
472 
473  private:
474 
475  void Subscribe(uint32_t aIndex);
476  void Unsubscribe();
477 
478  // libplayerc data structure
479  playerc_bumper_t *mDevice;
480 
481  public:
482 
483  BumperProxy(PlayerClient *aPc, uint32_t aIndex=0);
484  ~BumperProxy();
485 
486  uint32_t GetCount() const { return GetVar(mDevice->bumper_count); };
487 
489  uint32_t IsBumped(uint32_t aIndex) const
490  { return GetVar(mDevice->bumpers[aIndex]); };
491 
493  bool IsAnyBumped();
494 
496  void RequestBumperConfig();
497 
499  uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
500 
502  player_bumper_define_t GetPose(uint32_t aIndex) const
503  { return GetVar(mDevice->poses[aIndex]); };
504 
509  bool operator [](uint32_t aIndex) const
510  { return IsBumped(aIndex) != 0 ? true : false; }
511 
512 };
513 
517 class PLAYERCC_EXPORT CameraProxy : public ClientProxy
518 {
519 
520  private:
521 
522  virtual void Subscribe(uint32_t aIndex);
523  virtual void Unsubscribe();
524 
525  // libplayerc data structure
526  playerc_camera_t *mDevice;
527 
528  std::string mPrefix;
529  int mFrameNo;
530 
531  public:
532 
534  CameraProxy (PlayerClient *aPc, uint32_t aIndex=0);
535 
536  virtual ~CameraProxy();
537 
541  void SaveFrame(const std::string aPrefix, uint32_t aWidth=4);
542 
544  void Decompress();
545 
547  uint32_t GetDepth() const { return GetVar(mDevice->bpp); };
548 
550  uint32_t GetWidth() const { return GetVar(mDevice->width); };
551 
553  uint32_t GetHeight() const { return GetVar(mDevice->height); };
554 
561  uint32_t GetFormat() const { return GetVar(mDevice->format); };
562 
564  uint32_t GetImageSize() const { return GetVar(mDevice->image_count); };
565 
570  void GetImage(uint8_t* aImage) const
571  {
572  return GetVarByRef(mDevice->image,
573  mDevice->image+GetVar(mDevice->image_count),
574  aImage);
575  };
576 
581  uint32_t GetCompression() const { return GetVar(mDevice->compression); };
582 
583 };
584 
585 
590 class PLAYERCC_EXPORT DioProxy : public ClientProxy
591 {
592  private:
593 
594  void Subscribe(uint32_t aIndex);
595  void Unsubscribe();
596 
597  // libplayerc data structure
598  playerc_dio_t *mDevice;
599 
600  public:
602  DioProxy(PlayerClient *aPc, uint32_t aIndex=0);
604  ~DioProxy();
605 
607  uint32_t GetCount() const { return GetVar(mDevice->count); };
608 
610  uint32_t GetDigin() const { return GetVar(mDevice->digin); };
611 
613  bool GetInput(uint32_t aIndex) const;
614 
616  void SetOutput(uint32_t aCount, uint32_t aDigout);
617 
622  uint32_t operator [](uint32_t aIndex) const
623  { return GetInput(aIndex); }
624 };
625 
631 class PLAYERCC_EXPORT FiducialProxy : public ClientProxy
632 {
633  private:
634  void Subscribe(uint32_t aIndex);
635  void Unsubscribe();
636 
637  // libplayerc data structure
638  playerc_fiducial_t *mDevice;
639 
640  public:
642  FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0);
644  ~FiducialProxy();
645 
647  uint32_t GetCount() const { return GetVar(mDevice->fiducials_count); };
648 
651  { return GetVar(mDevice->fiducials[aIndex]);};
652 
655  { return GetVar(mDevice->fiducial_geom.pose);};
656 
659  { return GetVar(mDevice->fiducial_geom.size);};
660 
663  { return GetVar(mDevice->fiducial_geom.fiducial_size);};
664 
666  void RequestGeometry();
667 
672  player_fiducial_item_t operator [](uint32_t aIndex) const
673  { return GetFiducialItem(aIndex); }
674 };
675 
679 class PLAYERCC_EXPORT GpsProxy : public ClientProxy
680 {
681 
682  private:
683 
684  void Subscribe(uint32_t aIndex);
685  void Unsubscribe();
686 
687  // libplayerc data structure
688  playerc_gps_t *mDevice;
689 
690  public:
691 
692  // Constructor
693  GpsProxy(PlayerClient *aPc, uint32_t aIndex=0);
694 
695  ~GpsProxy();
696 
698  double GetLatitude() const { return GetVar(mDevice->lat); };
699  double GetLongitude() const { return GetVar(mDevice->lon); };
700 
702  double GetAltitude() const { return GetVar(mDevice->alt); };
703 
705  uint32_t GetSatellites() const { return GetVar(mDevice->sat_count); };
706 
708  uint32_t GetQuality() const { return GetVar(mDevice->quality); };
709 
711  double GetHdop() const { return GetVar(mDevice->hdop); };
712 
714  double GetVdop() const { return GetVar(mDevice->vdop); };
715 
717  double GetUtmEasting() const { return GetVar(mDevice->utm_e); };
718  double GetUtmNorthing() const { return GetVar(mDevice->utm_n); };
719 
721  double GetTime() const { return GetVar(mDevice->utc_time); };
722 
724  double GetErrHorizontal() const { return GetVar(mDevice->err_horz); };
725  double GetErrVertical() const { return GetVar(mDevice->err_vert); };
726 };
727 
735 class PLAYERCC_EXPORT Graphics2dProxy : public ClientProxy
736 {
737 
738  private:
739 
740  // Subscribe
741  void Subscribe(uint32_t aIndex);
742  // Unsubscribe
743  void Unsubscribe();
744 
745  // libplayerc data structure
746  playerc_graphics2d_t *mDevice;
747 
748  public:
749  // Constructor
750  Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
751  // Destructor
752  ~Graphics2dProxy();
753 
755  void Color(player_color_t col);
756 
758  void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
759 
761  void Clear(void);
762 
764  void DrawPoints(player_point_2d_t pts[], int count);
765 
767  void DrawPolygon(player_point_2d_t pts[],
768  int count,
769  bool filled,
770  player_color_t fill_color);
771 
773  void DrawPolyline(player_point_2d_t pts[], int count);
774 };
775 
781 class PLAYERCC_EXPORT Graphics3dProxy : public ClientProxy
782 {
783 
784  private:
785 
786  // Subscribe
787  void Subscribe(uint32_t aIndex);
788  // Unsubscribe
789  void Unsubscribe();
790 
791  // libplayerc data structure
792  playerc_graphics3d_t *mDevice;
793 
794  public:
795  // Constructor
796  Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
797  // Destructor
798  ~Graphics3dProxy();
799 
801  void Color(player_color_t col);
802 
804  void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
805 
807  void Clear(void);
808 
810  void Draw(player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count);
811 
812 };
813 
818 class PLAYERCC_EXPORT GripperProxy : public ClientProxy
819 {
820 
821  private:
822 
823  void Subscribe(uint32_t aIndex);
824  void Unsubscribe();
825 
826  // libplayerc data structure
827  playerc_gripper_t *mDevice;
828 
829  public:
830 
832  GripperProxy(PlayerClient *aPc, uint32_t aIndex=0);
834  ~GripperProxy();
835 
838  void RequestGeometry(void);
839 
841  uint32_t GetState() const { return GetVar(mDevice->state); };
843  uint32_t GetBeams() const { return GetVar(mDevice->beams); };
845  player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
847  player_bbox3d_t GetOuterSize() const { return GetVar(mDevice->outer_size); };
849  player_bbox3d_t GetInnerSize() const { return GetVar(mDevice->inner_size); };
851  uint32_t GetNumBeams() const { return GetVar(mDevice->num_beams); };
853  uint32_t GetCapacity() const { return GetVar(mDevice->capacity); };
855  uint32_t GetStored() const { return GetVar(mDevice->stored); };
856 
858  void Open();
860  void Close();
862  void Stop();
864  void Store();
866  void Retrieve();
867 };
868 
871 class PLAYERCC_EXPORT HealthProxy : public ClientProxy
872 {
873 
874  private:
875 
876  void Subscribe(uint32_t aIndex);
877  void Unsubscribe();
878 
879  // libplayerc data structure
880  playerc_health_t *mDevice;
881 
882  public:
884  HealthProxy(PlayerClient *aPc, uint32_t aIndex=0);
886  ~HealthProxy();
887 
889  float GetIdleCPU();
890 
892  float GetSystemCPU();
893 
895  float GetUserCPU();
896 
898  int64_t GetMemTotal();
899 
901  int64_t GetMemUsed();
902 
904  int64_t GetMemFree();
905 
907  int64_t GetSwapTotal();
908 
910  int64_t GetSwapUsed();
911 
913  int64_t GetSwapFree();
914 
916  float GetPercMemUsed();
917 
919  float GetPercSwapUsed();
920 
922  float GetPercTotalUsed();
923 };
924 
925 
926 
931 class PLAYERCC_EXPORT ImuProxy : public ClientProxy
932 {
933  private:
934  void Subscribe(uint32_t aIndex);
935  void Unsubscribe();
936 
937  // libplayerc data structure
938  playerc_imu_t *mDevice;
939 
940  public:
941 
943  ImuProxy(PlayerClient *aPc, uint32_t aIndex=0);
945  ~ImuProxy();
946 
948  player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
950  float GetXAccel();
951  float GetYAccel();
952  float GetZAccel();
953  float GetXGyro();
954  float GetYGyro();
955  float GetZGyro();
956  float GetXMagn();
957  float GetYMagn();
958  float GetZMagn();
959 
960  player_imu_data_calib_t GetRawValues() const
961  { return GetVar(mDevice->calib_data); };
962 
964  void SetDatatype(int aDatatype);
965 
967  void ResetOrientation(int aValue);
968 
969 
970 };
971 
972 
977 class PLAYERCC_EXPORT IrProxy : public ClientProxy
978 {
979 
980  private:
981 
982  void Subscribe(uint32_t aIndex);
983  void Unsubscribe();
984 
985  // libplayerc data structure
986  playerc_ir_t *mDevice;
987 
988  public:
989 
991  IrProxy(PlayerClient *aPc, uint32_t aIndex=0);
993  ~IrProxy();
994 
996  uint32_t GetCount() const { return GetVar(mDevice->data.ranges_count); };
998  double GetRange(uint32_t aIndex) const
999  { return GetVar(mDevice->data.ranges[aIndex]); };
1001  double GetVoltage(uint32_t aIndex) const
1002  { return GetVar(mDevice->data.voltages[aIndex]); };
1004  uint32_t GetPoseCount() const { return GetVar(mDevice->poses.poses_count); };
1006  player_pose3d_t GetPose(uint32_t aIndex) const
1007  {return GetVar(mDevice->poses.poses[aIndex]);};
1008 
1010  void RequestGeom();
1011 
1016  double operator [](uint32_t aIndex) const
1017  { return GetRange(aIndex); }
1018 
1019 };
1020 
1026 class PLAYERCC_EXPORT LaserProxy : public ClientProxy
1027 {
1028  private:
1029 
1030  void Subscribe(uint32_t aIndex);
1031  void Unsubscribe();
1032 
1033  // libplayerc data structure
1034  playerc_laser_t *mDevice;
1035 
1036  // local storage of config
1037  double min_angle, max_angle, scan_res, range_res, scanning_frequency;
1038  bool intensity;
1039 
1040  public:
1041 
1043  LaserProxy(PlayerClient *aPc, uint32_t aIndex=0);
1045  ~LaserProxy();
1046 
1048  uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
1049 
1051  double GetMaxRange() const { return GetVar(mDevice->max_range); };
1052 
1054  double GetScanRes() const { return GetVar(mDevice->scan_res); };
1055 
1057  double GetRangeRes() const { return GetVar(mDevice->range_res); };
1058 
1060  double GetScanningFrequency() const { return GetVar(mDevice->scanning_frequency); };
1061 
1063  double GetMinAngle() const { return GetVar(mDevice->scan_start); };
1065  double GetMaxAngle() const
1066  {
1067  scoped_lock_t lock(mPc->mMutex);
1068  return mDevice->scan_start + (mDevice->scan_count - 1)*mDevice->scan_res;
1069  };
1070 
1072  double GetConfMinAngle() const { return min_angle; };
1074  double GetConfMaxAngle() const { return max_angle; };
1075 
1077  bool IntensityOn() const { return GetVar(mDevice->intensity_on) != 0 ? true : false; };
1078 
1079 // /// Scan data (polar): range (m) and bearing (radians)
1080 // double GetScan(uint32_t aIndex) const
1081 // { return GetVar(mDevice->scan[aIndex]); };
1082 
1084  player_point_2d_t GetPoint(uint32_t aIndex) const
1085  { return GetVar(mDevice->point[aIndex]); };
1086 
1087 
1089  double GetRange(uint32_t aIndex) const
1090  { return GetVar(mDevice->ranges[aIndex]); };
1091 
1093  double GetBearing(uint32_t aIndex) const
1094  { return GetVar(mDevice->scan[aIndex][1]); };
1095 
1096 
1098  int GetIntensity(uint32_t aIndex) const
1099  { return GetVar(mDevice->intensity[aIndex]); };
1100 
1102  int GetID() const
1103  { return GetVar(mDevice->laser_id); };
1104 
1105 
1114  void Configure(double aMinAngle,
1115  double aMaxAngle,
1116  uint32_t aScanRes,
1117  uint32_t aRangeRes,
1118  bool aIntensity,
1119  double aScanningFrequency);
1120 
1123  void RequestConfigure();
1124 
1126  void RequestID();
1127 
1130  void RequestGeom();
1131 
1135  {
1136  player_pose3d_t p;
1137  scoped_lock_t lock(mPc->mMutex);
1138 
1139  p.px = mDevice->pose[0];
1140  p.py = mDevice->pose[1];
1141  p.pyaw = mDevice->pose[2];
1142  return(p);
1143  }
1144 
1148  {
1149  player_pose3d_t p;
1150  scoped_lock_t lock(mPc->mMutex);
1151 
1152  p.px = mDevice->robot_pose[0];
1153  p.py = mDevice->robot_pose[1];
1154  p.pyaw = mDevice->robot_pose[2];
1155  return(p);
1156  }
1157 
1160  {
1161  player_bbox3d_t b;
1162  scoped_lock_t lock(mPc->mMutex);
1163 
1164  b.sl = mDevice->size[0];
1165  b.sw = mDevice->size[1];
1166  return(b);
1167  }
1168 
1170  double GetMinLeft() const
1171  { return GetVar(mDevice->min_left); };
1172 
1174  double GetMinRight() const
1175  { return GetVar(mDevice->min_right); };
1176 
1178  double MinLeft () const
1179  { return GetMinLeft(); }
1180 
1182  double MinRight () const
1183  { return GetMinRight(); }
1184 
1189  double operator [] (uint32_t index) const
1190  { return GetRange(index);}
1191 
1192 };
1193 
1194 
1199 class PLAYERCC_EXPORT LimbProxy : public ClientProxy
1200 {
1201  private:
1202 
1203  void Subscribe(uint32_t aIndex);
1204  void Unsubscribe();
1205 
1206  // libplayerc data structure
1207  playerc_limb_t *mDevice;
1208 
1209  public:
1210 
1211  LimbProxy(PlayerClient *aPc, uint32_t aIndex=0);
1212  ~LimbProxy();
1213 
1216  void RequestGeometry(void);
1217 
1219  void SetPowerConfig(bool aVal);
1221  void SetBrakesConfig(bool aVal);
1223  void SetSpeedConfig(float aSpeed);
1224 
1226  void MoveHome(void);
1228  void Stop(void);
1230  void SetPose(float aPX, float aPY, float aPZ,
1231  float aAX, float aAY, float aAZ,
1232  float aOX, float aOY, float aOZ);
1234  void SetPosition(float aX, float aY, float aZ);
1237  void VectorMove(float aX, float aY, float aZ, float aLength);
1238 
1240  player_limb_data_t GetData(void) const;
1242  player_limb_geom_req_t GetGeom(void) const;
1243 };
1244 
1245 
1251 class PLAYERCC_EXPORT LinuxjoystickProxy : public ClientProxy
1252 {
1253  private:
1254 
1255  void Subscribe(uint32_t aIndex);
1256  void Unsubscribe();
1257 
1258  // libplayerc data structure
1259  playerc_joystick_t *mDevice;
1260 
1261  public:
1263  LinuxjoystickProxy(PlayerClient *aPc, uint32_t aIndex=0);
1265  ~LinuxjoystickProxy();
1266 
1268  uint32_t GetButtons() const { return GetVar(mDevice->buttons); };
1269 
1271  double GetAxes(uint32_t aIndex) const
1272  { if (GetVar(mDevice->axes_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->pos[aIndex]); };
1275  double operator [] (uint32_t aIndex) const { return GetAxes(aIndex); }
1276 
1278  uint32_t GetAxesCount() const { return GetVar(mDevice->axes_count); };
1279 
1281 // player_pose3d_t GetPose(uint32_t aIndex) const
1282 // { return GetVar(mDevice->poses[aIndex]); };
1283 
1284  // Enable/disable the joysticks.
1285  // Set @p state to 1 to enable, 0 to disable.
1286  // Note that when joysticks are disabled the client will still receive joystick
1287  // data, but the ranges will always be the last value read from the joysticks
1288  // before they were disabled.
1289  //void SetEnable(bool aEnable);
1290 
1292 // void RequestGeom();
1293 };
1294 
1295 
1301 class PLAYERCC_EXPORT LocalizeProxy : public ClientProxy
1302 {
1303 
1304  private:
1305 
1306  void Subscribe(uint32_t aIndex);
1307  void Unsubscribe();
1308 
1309  // libplayerc data structure
1310  playerc_localize_t *mDevice;
1311 
1312  public:
1313 
1315  LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0);
1317  ~LocalizeProxy();
1318 
1320  // @todo should these be in a player_pose_t?
1321  uint32_t GetMapSizeX() const { return GetVar(mDevice->map_size_x); };
1322  uint32_t GetMapSizeY() const { return GetVar(mDevice->map_size_y); };
1323 
1324  // @todo should these be in a player_pose_t?
1325  uint32_t GetMapTileX() const { return GetVar(mDevice->map_tile_x); };
1326  uint32_t GetMapTileY() const { return GetVar(mDevice->map_tile_y); };
1327 
1329  double GetMapScale() const { return GetVar(mDevice->map_scale); };
1330 
1331  // Map data (empty = -1, unknown = 0, occupied = +1)
1332  // is this still needed? if so,
1333  //void GetMapCells(uint8_t* aCells) const
1334  //{
1335  // return GetVarByRef(mDevice->map_cells,
1336  // mDevice->image+GetVar(mDevice->??map_cell_cout??),
1337  // aCells);
1338  //};
1339 
1341  uint32_t GetPendingCount() const { return GetVar(mDevice->pending_count); };
1342 
1344  uint32_t GetHypothCount() const { return GetVar(mDevice->hypoth_count); };
1345 
1347  player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
1348  { return GetVar(mDevice->hypoths[aIndex]); };
1349 
1352  { return playerc_localize_get_particles(mDevice); }
1353 
1355  player_pose2d_t GetParticlePose(int index) const;
1356 
1358  void SetPose(double pose[3], double cov[3]);
1359 
1361  uint32_t GetNumHypoths() const { return GetVar(mDevice->hypoth_count); };
1362 
1365  uint32_t GetNumParticles() const { return GetVar(mDevice->num_particles); };
1366 };
1367 
1368 
1372 class PLAYERCC_EXPORT LogProxy : public ClientProxy
1373 {
1374  private:
1375 
1376  void Subscribe(uint32_t aIndex);
1377  void Unsubscribe();
1378 
1379  // libplayerc data structure
1380  playerc_log_t *mDevice;
1381 
1382  public:
1384  LogProxy(PlayerClient *aPc, uint32_t aIndex=0);
1385 
1387  ~LogProxy();
1388 
1391  int GetType() const { return GetVar(mDevice->type); };
1392 
1394  int GetState() const { return GetVar(mDevice->state); };
1395 
1397  void QueryState();
1398 
1401  void SetState(int aState);
1402 
1404  void SetWriteState(int aState);
1405 
1407  void SetReadState(int aState);
1408 
1410  void Rewind();
1411 
1413  void SetFilename(const std::string aFilename);
1414 };
1415 
1419 class PLAYERCC_EXPORT MapProxy : public ClientProxy
1420 {
1421  private:
1422 
1423  void Subscribe(uint32_t aIndex);
1424  void Unsubscribe();
1425 
1426  // libplayerc data structure
1427  playerc_map_t *mDevice;
1428 
1429  public:
1431  MapProxy(PlayerClient *aPc, uint32_t aIndex=0);
1432 
1434  ~MapProxy();
1435 
1437  void RequestMap();
1438 
1440  int GetCellIndex(int x, int y) const
1441  { return y*GetWidth() + x; };
1442 
1444  int8_t GetCell(int x, int y) const
1445  { return GetVar(mDevice->cells[GetCellIndex(x,y)]); };
1446 
1448  double GetResolution() const { return GetVar(mDevice->resolution); };
1449 
1452  uint32_t GetWidth() const { return GetVar(mDevice->width); };
1455  uint32_t GetHeight() const { return GetVar(mDevice->height); };
1456 
1457  double GetOriginX() const { return GetVar(mDevice->origin[0]); };
1458  double GetOriginY() const { return GetVar(mDevice->origin[1]); };
1459 
1461  void GetMap(int8_t* aMap) const
1462  {
1463  return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->cells),
1464  reinterpret_cast<int8_t*>(mDevice->cells+GetWidth()*GetHeight()),
1465  aMap);
1466  };
1467 };
1468 
1474 class PLAYERCC_EXPORT OpaqueProxy : public ClientProxy
1475 {
1476 
1477  private:
1478 
1479  void Subscribe(uint32_t aIndex);
1480  void Unsubscribe();
1481 
1482  // libplayerc data structure
1483  playerc_opaque_t *mDevice;
1484 
1485  public:
1486 
1488  OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0);
1490  ~OpaqueProxy();
1491 
1493  uint32_t GetCount() const { return GetVar(mDevice->data_count); };
1494 
1496  void GetData(uint8_t* aDest) const
1497  {
1498  return GetVarByRef(mDevice->data,
1499  mDevice->data+GetVar(mDevice->data_count),
1500  aDest);
1501  };
1502 
1504  void SendCmd(player_opaque_data_t* aData);
1505 
1507  int SendReq(player_opaque_data_t* aRequest);
1508 
1509 };
1510 
1514 class PLAYERCC_EXPORT PlannerProxy : public ClientProxy
1515 {
1516 
1517  private:
1518 
1519  void Subscribe(uint32_t aIndex);
1520  void Unsubscribe();
1521 
1522  // libplayerc data structure
1523  playerc_planner_t *mDevice;
1524 
1525  public:
1526 
1528  PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0);
1530  ~PlannerProxy();
1531 
1533  void SetGoalPose(double aGx, double aGy, double aGa);
1534 
1537  void RequestWaypoints();
1538 
1541  void SetEnable(bool aEnable);
1542 
1544  uint32_t GetPathValid() const { return GetVar(mDevice->path_valid); };
1545 
1547  uint32_t GetPathDone() const { return GetVar(mDevice->path_done); };
1548 
1551  double GetPx() const { return GetVar(mDevice->px); };
1554  double GetPy() const { return GetVar(mDevice->py); };
1557  double GetPa() const { return GetVar(mDevice->pa); };
1558 
1561  {
1562  player_pose2d_t p;
1563  scoped_lock_t lock(mPc->mMutex);
1564  p.px = mDevice->px;
1565  p.py = mDevice->py;
1566  p.pa = mDevice->pa;
1567  return(p);
1568  }
1569 
1572  double GetGx() const { return GetVar(mDevice->gx); };
1575  double GetGy() const { return GetVar(mDevice->gy); };
1578  double GetGa() const { return GetVar(mDevice->ga); };
1579 
1582  {
1583  player_pose2d_t p;
1584  scoped_lock_t lock(mPc->mMutex);
1585  p.px = mDevice->gx;
1586  p.py = mDevice->gy;
1587  p.pa = mDevice->ga;
1588  return(p);
1589  }
1590 
1593  double GetWx() const { return GetVar(mDevice->wx); };
1596  double GetWy() const { return GetVar(mDevice->wy); };
1599  double GetWa() const { return GetVar(mDevice->wa); };
1600 
1603  {
1604  player_pose2d_t p;
1605  scoped_lock_t lock(mPc->mMutex);
1606  p.px = mDevice->wx;
1607  p.py = mDevice->wy;
1608  p.pa = mDevice->wa;
1609  return(p);
1610  }
1611 
1614  double GetIx(int i) const;
1617  double GetIy(int i) const;
1620  double GetIa(int i) const;
1621 
1623  player_pose2d_t GetWaypoint(uint32_t aIndex) const
1624  {
1625  assert(aIndex < GetWaypointCount());
1626  player_pose2d_t p;
1627  scoped_lock_t lock(mPc->mMutex);
1628  p.px = mDevice->waypoints[aIndex][0];
1629  p.py = mDevice->waypoints[aIndex][1];
1630  p.pa = mDevice->waypoints[aIndex][2];
1631  return(p);
1632  }
1633 
1638  { return GetVar(mDevice->curr_waypoint); };
1639 
1641  uint32_t GetWaypointCount() const
1642  { return GetVar(mDevice->waypoint_count); };
1643 
1648  player_pose2d_t operator [](uint32_t aIndex) const
1649  { return GetWaypoint(aIndex); }
1650 
1651 };
1652 
1656 class PLAYERCC_EXPORT Pointcloud3dProxy : public ClientProxy
1657 {
1658  private:
1659 
1660  void Subscribe(uint32_t aIndex);
1661  void Unsubscribe();
1662 
1663  // libplayerc data structure
1664  playerc_pointcloud3d_t *mDevice;
1665 
1666  public:
1668  Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1669 
1671  ~Pointcloud3dProxy();
1672 
1674  uint32_t GetCount() const { return GetVar(mDevice->points_count); };
1675 
1678  { return GetVar(mDevice->points[aIndex]); };
1679 
1682  player_pointcloud3d_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); }
1683 
1684 };
1685 
1686 
1691 class PLAYERCC_EXPORT Position1dProxy : public ClientProxy
1692 {
1693 
1694  private:
1695 
1696  void Subscribe(uint32_t aIndex);
1697  void Unsubscribe();
1698 
1699  // libplayerc data structure
1700  playerc_position1d_t *mDevice;
1701 
1702  public:
1703 
1705  Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1707  ~Position1dProxy();
1708 
1712  void SetSpeed(double aVel);
1713 
1717  void GoTo(double aPos, double aVel);
1718 
1721  void RequestGeom();
1722 
1725  {
1726  player_pose3d_t p;
1727  scoped_lock_t lock(mPc->mMutex);
1728  p.px = mDevice->pose[0];
1729  p.py = mDevice->pose[1];
1730  p.pyaw = mDevice->pose[2];
1731  return(p);
1732  }
1733 
1736  {
1737  player_bbox3d_t b;
1738  scoped_lock_t lock(mPc->mMutex);
1739  b.sl = mDevice->size[0];
1740  b.sw = mDevice->size[1];
1741  return(b);
1742  }
1743 
1748  void SetMotorEnable(bool enable);
1749 
1752  void SetOdometry(double aPos);
1753 
1755  void ResetOdometry() { SetOdometry(0); };
1756 
1758  //void SetSpeedPID(double kp, double ki, double kd);
1759 
1761  //void SetPositionPID(double kp, double ki, double kd);
1762 
1765  //void SetPositionSpeedProfile(double spd, double acc);
1766 
1768  double GetPos() const { return GetVar(mDevice->pos); };
1769 
1771  double GetVel() const { return GetVar(mDevice->vel); };
1772 
1774  bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
1775 
1777  uint8_t GetStatus() const { return GetVar(mDevice->status); };
1778 
1780  bool IsLimitMin() const
1781  { return (GetVar(mDevice->status) &
1782  (1 << PLAYER_POSITION1D_STATUS_LIMIT_MIN)) > 0; };
1783 
1785  bool IsLimitCen() const
1786  { return (GetVar(mDevice->status) &
1787  (1 << PLAYER_POSITION1D_STATUS_LIMIT_CEN)) > 0; };
1788 
1790  bool IsLimitMax() const
1791  { return (GetVar(mDevice->status) &
1792  (1 << PLAYER_POSITION1D_STATUS_LIMIT_MAX)) > 0; };
1793 
1795  bool IsOverCurrent() const
1796  { return (GetVar(mDevice->status) &
1797  (1 << PLAYER_POSITION1D_STATUS_OC)) > 0; };
1798 
1800  bool IsTrajComplete() const
1801  { return (GetVar(mDevice->status) &
1803 
1805  bool IsEnabled() const
1806  { return (GetVar(mDevice->status) &
1807  (1 << PLAYER_POSITION1D_STATUS_ENABLED)) > 0; };
1808 
1809 };
1810 
1815 class PLAYERCC_EXPORT Position2dProxy : public ClientProxy
1816 {
1817 
1818  private:
1819 
1820  void Subscribe(uint32_t aIndex);
1821  void Unsubscribe();
1822 
1823  // libplayerc data structure
1824  playerc_position2d_t *mDevice;
1825 
1826  public:
1827 
1829  Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1831  ~Position2dProxy();
1832 
1836  void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed);
1837 
1840  void SetSpeed(double aXSpeed, double aYawSpeed)
1841  { return SetSpeed(aXSpeed, 0, aYawSpeed);}
1842 
1845  { return SetSpeed(vel.px, vel.py, vel.pa);}
1846 
1850  void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead);
1851 
1854  void SetVelHead(double aXSpeed, double aYawHead)
1855  { return SetVelHead(aXSpeed, 0, aYawHead);}
1856 
1857 
1861  void GoTo(player_pose2d_t pos, player_pose2d_t vel);
1862 
1865  { player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
1866 
1869  void GoTo(double aX, double aY, double aYaw)
1870  { player_pose2d_t pos = {aX,aY,aYaw}; player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
1871 
1873  void SetCarlike(double aXSpeed, double aDriveAngle);
1874 
1877  void RequestGeom();
1878 
1880  // body (fill it in by calling RequestGeom()).
1882  {
1883  player_pose3d_t p;
1884  scoped_lock_t lock(mPc->mMutex);
1885  p.px = mDevice->pose[0];
1886  p.py = mDevice->pose[1];
1887  p.pyaw = mDevice->pose[2];
1888  return(p);
1889  }
1890 
1893  {
1894  player_bbox3d_t b;
1895  scoped_lock_t lock(mPc->mMutex);
1896  b.sl = mDevice->size[0];
1897  b.sw = mDevice->size[1];
1898  return(b);
1899  }
1900 
1905  void SetMotorEnable(bool enable);
1906 
1907  // Select velocity control mode.
1908  //
1909  // For the the p2os_position driver, set @p mode to 0 for direct wheel
1910  // velocity control (default), or 1 for separate translational and
1911  // rotational control.
1912  //
1913  // For the reb_position driver: 0 is direct velocity control, 1 is for
1914  // velocity-based heading PD controller (uses DoDesiredHeading()).
1915  //void SelectVelocityControl(unsigned char mode);
1916 
1918  void ResetOdometry();
1919 
1922  //void SelectPositionMode(unsigned char mode);
1923 
1926  void SetOdometry(double aX, double aY, double aYaw);
1927 
1929  //void SetSpeedPID(double kp, double ki, double kd);
1930 
1932  //void SetPositionPID(double kp, double ki, double kd);
1933 
1936  //void SetPositionSpeedProfile(double spd, double acc);
1937 
1938  //
1939  // void DoStraightLine(double m);
1940 
1941  //
1942  //void DoRotation(double yawspeed);
1943 
1944  //
1945  //void DoDesiredHeading(double yaw, double xspeed, double yawspeed);
1946 
1947  //
1948  //void SetStatus(uint8_t cmd, uint16_t value);
1949 
1950  //
1951  //void PlatformShutdown();
1952 
1954  double GetXPos() const { return GetVar(mDevice->px); };
1955 
1957  double GetYPos() const { return GetVar(mDevice->py); };
1958 
1960  double GetYaw() const { return GetVar(mDevice->pa); };
1961 
1963  double GetXSpeed() const { return GetVar(mDevice->vx); };
1964 
1966  double GetYSpeed() const { return GetVar(mDevice->vy); };
1967 
1969  double GetYawSpeed() const { return GetVar(mDevice->va); };
1970 
1972  bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
1973 
1974 };
1975 
1982 class PLAYERCC_EXPORT Position3dProxy : public ClientProxy
1983 {
1984 
1985  private:
1986 
1987  void Subscribe(uint32_t aIndex);
1988  void Unsubscribe();
1989 
1990  // libplayerc data structure
1991  playerc_position3d_t *mDevice;
1992 
1993  public:
1994 
1996  Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1998  ~Position3dProxy();
1999 
2003  void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed,
2004  double aRollSpeed, double aPitchSpeed, double aYawSpeed);
2005 
2009  void SetSpeed(double aXSpeed, double aYSpeed,
2010  double aZSpeed, double aYawSpeed)
2011  { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
2012 
2014  void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
2015  { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
2016 
2019  void SetSpeed(double aXSpeed, double aYawSpeed)
2020  { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
2021 
2024  { SetSpeed(vel.px,vel.py,vel.pz,vel.proll,vel.ppitch,vel.pyaw);}
2025 
2029  void GoTo(player_pose3d_t aPos, player_pose3d_t aVel);
2030 
2033  { player_pose3d_t vel = {0,0,0,0,0,0}; GoTo(aPos, vel); }
2034 
2035 
2038  void GoTo(double aX, double aY, double aZ,
2039  double aRoll, double aPitch, double aYaw)
2040  { player_pose3d_t pos = {aX,aY,aZ,aRoll,aPitch,aYaw};
2041  player_pose3d_t vel = {0,0,0,0,0,0};
2042  GoTo(pos, vel);
2043  }
2044 
2049  void SetMotorEnable(bool aEnable);
2050 
2053  void SelectVelocityControl(int aMode);
2054 
2056  void ResetOdometry();
2057 
2061  void SetOdometry(double aX, double aY, double aZ,
2062  double aRoll, double aPitch, double aYaw);
2063 
2066  void RequestGeom();
2067 
2068  // Select position mode
2069  // Set @p mode for 0 for velocity mode, 1 for position mode.
2070  //void SelectPositionMode(unsigned char mode);
2071 
2072  //
2073  //void SetSpeedPID(double kp, double ki, double kd);
2074 
2075  //
2076  //void SetPositionPID(double kp, double ki, double kd);
2077 
2078  // Sets the ramp profile for position based control
2079  // spd rad/s, acc rad/s/s
2080  //void SetPositionSpeedProfile(double spd, double acc);
2081 
2083  double GetXPos() const { return GetVar(mDevice->pos_x); };
2084 
2086  double GetYPos() const { return GetVar(mDevice->pos_y); };
2087 
2089  double GetZPos() const { return GetVar(mDevice->pos_z); };
2090 
2092  double GetRoll() const { return GetVar(mDevice->pos_roll); };
2093 
2095  double GetPitch() const { return GetVar(mDevice->pos_pitch); };
2096 
2098  double GetYaw() const { return GetVar(mDevice->pos_yaw); };
2099 
2101  double GetXSpeed() const { return GetVar(mDevice->vel_x); };
2102 
2104  double GetYSpeed() const { return GetVar(mDevice->vel_y); };
2105 
2107  double GetZSpeed() const { return GetVar(mDevice->vel_z); };
2108 
2110  double GetRollSpeed() const { return GetVar(mDevice->vel_roll); };
2111 
2113  double GetPitchSpeed() const { return GetVar(mDevice->vel_pitch); };
2114 
2116  double GetYawSpeed() const { return GetVar(mDevice->vel_yaw); };
2117 
2119  bool GetStall () const { return GetVar(mDevice->stall) != 0 ? true : false; };
2120 };
2123 class PLAYERCC_EXPORT PowerProxy : public ClientProxy
2124 {
2125  private:
2126 
2127  void Subscribe(uint32_t aIndex);
2128  void Unsubscribe();
2129 
2130  // libplayerc data structure
2131  playerc_power_t *mDevice;
2132 
2133  public:
2135  PowerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2137  ~PowerProxy();
2138 
2140  double GetCharge() const { return GetVar(mDevice->charge); };
2141 
2143  double GetPercent() const {return GetVar(mDevice->percent); };
2144 
2146  double GetJoules() const {return GetVar(mDevice->joules); };
2147 
2149  double GetWatts() const {return GetVar(mDevice->watts); };
2150 
2152  bool GetCharging() const {return GetVar(mDevice->charging) != 0 ? true : false;};
2153 
2154  // Return whether the power data is valid
2155  bool IsValid() const {return GetVar(mDevice->valid) != 0 ? true : false;};
2156 };
2157 
2164 class PLAYERCC_EXPORT PtzProxy : public ClientProxy
2165 {
2166 
2167  private:
2168 
2169  void Subscribe(uint32_t aIndex);
2170  void Unsubscribe();
2171 
2172  // libplayerc data structure
2173  playerc_ptz_t *mDevice;
2174 
2175  public:
2177  PtzProxy(PlayerClient *aPc, uint32_t aIndex=0);
2178  // destructor
2179  ~PtzProxy();
2180 
2181  public:
2182 
2186  void SetCam(double aPan, double aTilt, double aZoom);
2187 
2189  void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0);
2190 
2193  void SelectControlMode(uint32_t aMode);
2194 
2196  double GetPan() const { return GetVar(mDevice->pan); };
2198  double GetTilt() const { return GetVar(mDevice->tilt); };
2200  double GetZoom() const { return GetVar(mDevice->zoom); };
2201 
2203  int GetStatus();
2204 
2205 
2206 };
2207 
2210 class PLAYERCC_EXPORT RangerProxy : public ClientProxy
2211 {
2212  private:
2213 
2214  void Subscribe(uint32_t aIndex);
2215  void Unsubscribe();
2216 
2217  // libplayerc data structure
2218  playerc_ranger_t *mDevice;
2219 
2220  public:
2222  RangerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2224  ~RangerProxy();
2225 
2227  uint32_t GetElementCount() const { return GetVar(mDevice->element_count); };
2228 
2230  player_pose3d_t GetDevicePose() const { return GetVar(mDevice->device_pose); };
2232  player_bbox3d_t GetDeviceSize() const { return GetVar(mDevice->device_size); };
2233 
2235  player_pose3d_t GetElementPose(uint32_t aIndex) const;
2237  player_bbox3d_t GetElementSize(uint32_t aIndex) const;
2238 
2240  uint32_t GetRangeCount() const { return GetVar(mDevice->ranges_count); };
2242  double GetRange(uint32_t aIndex) const;
2244  double operator[] (uint32_t aIndex) const { return GetRange(aIndex); }
2245 
2247  uint32_t GetIntensityCount() const { return GetVar(mDevice->intensities_count); } ;
2249  double GetIntensity(uint32_t aIndex) const;
2250 
2253  void SetPower(bool aEnable);
2254 
2257  void SetIntensityData(bool aEnable);
2258 
2260  void RequestGeom();
2261 
2266  void Configure(double aMinAngle,
2267  double aMaxAngle,
2268  double aAngularRes,
2269  double aMinRange,
2270  double aMaxRange,
2271  double aRangeRes,
2272  double aFrequency);
2273 
2276  void RequestConfigure();
2277 
2279  double GetMinAngle() const { return GetVar(mDevice->min_angle); };
2280 
2282  double GetMaxAngle() const { return GetVar(mDevice->max_angle); };
2283 
2285  double GetAngularRes() const { return GetVar(mDevice->angular_res); };
2286 
2288  double GetMinRange() const { return GetVar(mDevice->min_range); };
2289 
2291  double GetMaxRange() const { return GetVar(mDevice->max_range); };
2292 
2294  double GetRangeRes() const { return GetVar(mDevice->range_res); };
2295 
2297  double GetFrequency() const { return GetVar(mDevice->frequency); };
2298 };
2299 
2302 class PLAYERCC_EXPORT RFIDProxy : public ClientProxy
2303 {
2304 
2305  private:
2306 
2307  void Subscribe(uint32_t aIndex);
2308  void Unsubscribe();
2309 
2310  // libplayerc data structure
2311  playerc_rfid_t *mDevice;
2312 
2313  public:
2315  RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0);
2317  ~RFIDProxy();
2318 
2320  uint32_t GetTagsCount() const { return GetVar(mDevice->tags_count); };
2322  playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
2323  { return GetVar(mDevice->tags[aIndex]);};
2324 
2329  playerc_rfidtag_t operator [](uint32_t aIndex) const
2330  { return(GetRFIDTag(aIndex)); }
2331 };
2332 
2337 class PLAYERCC_EXPORT SimulationProxy : public ClientProxy
2338 {
2339  private:
2340 
2341  void Subscribe(uint32_t aIndex);
2342  void Unsubscribe();
2343 
2344  // libplayerc data structure
2345  playerc_simulation_t *mDevice;
2346 
2347  public:
2349  SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0);
2351  ~SimulationProxy();
2352 
2355  void SetPose2d(char* identifier, double x, double y, double a);
2356 
2359  void GetPose2d(char* identifier, double& x, double& y, double& a);
2360 
2363  void SetPose3d(char* identifier, double x, double y, double z,
2364  double roll, double pitch, double yaw);
2365 
2368  void GetPose3d(char* identifier, double& x, double& y, double& z,
2369  double& roll, double& pitch, double& yaw, double& time);
2370 
2372  void GetProperty(char* identifier, char *name, void *value, size_t value_len );
2373 
2375  void SetProperty(char* identifier, char *name, void *value, size_t value_len );
2376 };
2377 
2378 
2384 class PLAYERCC_EXPORT SonarProxy : public ClientProxy
2385 {
2386  private:
2387 
2388  void Subscribe(uint32_t aIndex);
2389  void Unsubscribe();
2390 
2391  // libplayerc data structure
2392  playerc_sonar_t *mDevice;
2393 
2394  public:
2396  SonarProxy(PlayerClient *aPc, uint32_t aIndex=0);
2398  ~SonarProxy();
2399 
2401  uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
2402 
2404  double GetScan(uint32_t aIndex) const
2405  { if (GetVar(mDevice->scan_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->scan[aIndex]); };
2408  double operator [] (uint32_t aIndex) const { return GetScan(aIndex); }
2409 
2411  uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
2412 
2414  player_pose3d_t GetPose(uint32_t aIndex) const
2415  { return GetVar(mDevice->poses[aIndex]); };
2416 
2417  // Enable/disable the sonars.
2418  // Set @p state to 1 to enable, 0 to disable.
2419  // Note that when sonars are disabled the client will still receive sonar
2420  // data, but the ranges will always be the last value read from the sonars
2421  // before they were disabled.
2422  //void SetEnable(bool aEnable);
2423 
2425  void RequestGeom();
2426 };
2427 
2432 class PLAYERCC_EXPORT SpeechProxy : public ClientProxy
2433 {
2434 
2435  private:
2436 
2437  void Subscribe(uint32_t aIndex);
2438  void Unsubscribe();
2439 
2440  // libplayerc data structure
2441  playerc_speech_t *mDevice;
2442 
2443  public:
2445  SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0);
2447  ~SpeechProxy();
2448 
2451  void Say(std::string aStr);
2452 };
2453 
2457 class PLAYERCC_EXPORT SpeechRecognitionProxy : public ClientProxy
2458 {
2459  void Subscribe(uint32_t aIndex);
2460  void Unsubscribe();
2461 
2464  public:
2466  SpeechRecognitionProxy(PlayerClient *aPc, uint32_t aIndex=0);
2469  std::string GetWord(uint32_t aWord) const{
2470  scoped_lock_t lock(mPc->mMutex);
2471  return std::string(mDevice->words[aWord]);
2472  }
2473 
2475  uint32_t GetCount(void) const { return GetVar(mDevice->wordCount); }
2476 
2479  std::string operator [](uint32_t aWord) { return(GetWord(aWord)); }
2480 };
2481 
2485 class PLAYERCC_EXPORT VectorMapProxy : public ClientProxy
2486 {
2487 
2488  private:
2489 
2490  // Subscribe
2491  void Subscribe(uint32_t aIndex);
2492  // Unsubscribe
2493  void Unsubscribe();
2494 
2495  // libplayerc data structure
2496  playerc_vectormap_t *mDevice;
2497 
2498  bool map_info_cached;
2499  public:
2500  // Constructor
2501  VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0);
2502  // Destructor
2503  ~VectorMapProxy();
2504 
2505  void GetMapInfo();
2506  void GetLayerData(unsigned layer_index);
2507 
2508  int GetLayerCount() const;
2509  std::vector<std::string> GetLayerNames() const;
2510  int GetFeatureCount(unsigned layer_index) const;
2511  const uint8_t * GetFeatureData(unsigned layer_index, unsigned feature_index) const;
2512  size_t GetFeatureDataCount(unsigned layer_index, unsigned feature_index) const;
2513 };
2514 
2517 class PLAYERCC_EXPORT WiFiProxy: public ClientProxy
2518 {
2519 
2520  private:
2521 
2522  void Subscribe(uint32_t aIndex);
2523  void Unsubscribe();
2524 
2525  // libplayerc data structure
2526  playerc_wifi_t *mDevice;
2527 
2528  public:
2530  WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0);
2532  ~WiFiProxy();
2533 
2534  const playerc_wifi_link_t *GetLink(int aLink);
2535 
2536  int GetLinkCount() const { return mDevice->link_count; };
2537  char* GetOwnIP() const { return mDevice->ip; };
2538 
2539  char* GetLinkIP(int index) const { return (char*) mDevice->links[index].ip; };
2540  char* GetLinkMAC(int index) const { return (char*) mDevice->links[index].mac; };
2541  char* GetLinkESSID(int index) const { return (char*)mDevice->links[index].essid; };
2542  double GetLinkFreq(int index) const {return mDevice->links[index].freq;};
2543  int GetLinkMode(int index) const { return mDevice->links[index].mode; };
2544  int GetLinkEncrypt(int index) const {return mDevice->links[index].encrypt; };
2545  int GetLinkQuality(int index) const { return mDevice->links[index].qual; };
2546  int GetLinkLevel(int index) const {return mDevice->links[index].level; };
2547  int GetLinkNoise(int index) const {return mDevice->links[index].noise; } ;
2548 
2549  //player_wifi_link_t
2550 // int GetLinkQuality(char/// ip = NULL);
2551 // int GetLevel(char/// ip = NULL);
2552 // int GetLeveldBm(char/// ip = NULL) { return GetLevel(ip) - 0x100; }
2553 // int GetNoise(char/// ip = NULL);
2554 // int GetNoisedBm(char/// ip = NULL) { return GetNoise(ip) - 0x100; }
2555 //
2556 // uint16_t GetMaxLinkQuality() { return maxqual; }
2557 // uint8_t GetMode() { return op_mode; }
2558 //
2559 // int GetBitrate();
2560 //
2561 // char/// GetMAC(char *buf, int len);
2562 //
2563 // char/// GetIP(char *buf, int len);
2564 // char/// GetAP(char *buf, int len);
2565 //
2566 // int AddSpyHost(char *address);
2567 // int RemoveSpyHost(char *address);
2568 //
2569 // private:
2570 // int GetLinkIndex(char *ip);
2571 //
2572 // /// The current wifi data.
2573 // int link_count;
2574 // player_wifi_link_t links[PLAYER_WIFI_MAX_LINKS];
2575 // uint32_t throughput;
2576 // uint8_t op_mode;
2577 // int32_t bitrate;
2578 // uint16_t qual_type, maxqual, maxlevel, maxnoise;
2579 //
2580 // char access_point[32];
2581 };
2582 
2585 class PLAYERCC_EXPORT WSNProxy : public ClientProxy
2586 {
2587 
2588  private:
2589 
2590  void Subscribe(uint32_t aIndex);
2591  void Unsubscribe();
2592 
2593  // libplayerc data structure
2594  playerc_wsn_t *mDevice;
2595 
2596  public:
2598  WSNProxy(PlayerClient *aPc, uint32_t aIndex=0);
2600  ~WSNProxy();
2601 
2602  uint32_t GetNodeType () const { return GetVar(mDevice->node_type); };
2603  uint32_t GetNodeID () const { return GetVar(mDevice->node_id); };
2604  uint32_t GetNodeParentID() const { return GetVar(mDevice->node_parent_id); };
2605 
2607  GetNodeDataPacket() const { return GetVar(mDevice->data_packet); };
2608 
2609  void SetDevState(int nodeID, int groupID, int devNr, int value);
2610  void Power(int nodeID, int groupID, int value);
2611  void DataType(int value);
2612  void DataFreq(int nodeID, int groupID, float frequency);
2613 };
2614 
2616 }
2617 
2618 namespace std
2619 {
2620  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_point_2d_t& c);
2621  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose2d_t& c);
2622  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose3d_t& c);
2623  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox2d_t& c);
2624  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox3d_t& c);
2625  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_segment_t& c);
2626  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_extent2d_t& c);
2627  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const playerc_device_info_t& c);
2628 
2629  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ClientProxy& c);
2630  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ActArrayProxy& c);
2631  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AioProxy& c);
2632  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AudioProxy& a);
2633  //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlinkenLightProxy& c);
2634  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlobfinderProxy& c);
2635  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BumperProxy& c);
2636  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::CameraProxy& c);
2637  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::DioProxy& c);
2638  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::FiducialProxy& c);
2639  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GpsProxy& c);
2640  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GripperProxy& c);
2641  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ImuProxy& c);
2642  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::IrProxy& c);
2643  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LaserProxy& c);
2644  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LimbProxy& c);
2645  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LinuxjoystickProxy& c);
2646  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LocalizeProxy& c);
2647  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LogProxy& c);
2648  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::MapProxy& c);
2649  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::OpaqueProxy& c);
2650  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PlannerProxy& c);
2651  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position1dProxy& c);
2652  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position2dProxy& c);
2653  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position3dProxy& c);
2654  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PowerProxy& c);
2655  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PtzProxy& c);
2656  PLAYERCC_EXPORT std::ostream& operator << (std::ostream &os, const PlayerCc::RangerProxy &c);
2657  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SimulationProxy& c);
2658  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SonarProxy& c);
2659  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechProxy& c);
2660  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechRecognitionProxy& c);
2661  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::VectorMapProxy& c);
2662  //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WafeformProxy& c);
2663  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WiFiProxy& c);
2664  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::RFIDProxy& c);
2665  PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WSNProxy& c);
2666 }
2667 
2668 #endif
2669 
player_bbox3d_t GetOuterSize() const
Get the outer size of the gripper.
Definition: playerc++.h:847
Fiducial finder data.
Definition: playerc.h:1510
double GetBearing(uint32_t aIndex) const
get the bearing
Definition: playerc++.h:1093
Structure describing the WSN node&#39;s data packet.
Definition: player_interfaces.h:4335
The PlannerProxy proxy provides an interface to a 2D motion planner.
Definition: playerc++.h:1514
Opaque device data.
Definition: playerc.h:2459
int GetState() const
Is logging/playback enabled? Call QueryState() to fill it.
Definition: playerc++.h:1394
uint32_t GetBeams() const
Get the gripper break beam info.
Definition: playerc++.h:843
Planner device data.
Definition: playerc.h:2508
The AudioProxy class controls an audio device.
Definition: playerc++.h:245
player_pose3d_t GetPose(uint32_t aIndex) const
get a particular pose
Definition: playerc++.h:1006
Ir proxy data.
Definition: playerc.h:1865
RFID proxy data.
Definition: playerc.h:3433
Aio proxy data.
Definition: playerc.h:929
double GetResolution() const
Map resolution, m/cell.
Definition: playerc++.h:1448
uint32_t GetPoseCount() const
get the number of poses
Definition: playerc++.h:1004
data
Definition: player_interfaces.h:3414
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1159
double GetYaw() const
Accessor method.
Definition: playerc++.h:2098
player_pose3d_t GetPose(uint32_t aIndex) const
Sonar poses (m,m,radians)
Definition: playerc++.h:2414
uint32_t GetHeight() const
Map size, in cells.
Definition: playerc++.h:1455
Vectormap proxy.
Definition: playerc.h:2398
double ppitch
pitch [rad]
Definition: player.h:235
The SimulationProxy proxy provides access to a simulation device.
Definition: playerc++.h:2337
Vectormap feature data.
Definition: player.h:261
A rectangular bounding box, used to define the size of an object.
Definition: player.h:250
void SetSpeed(player_pose2d_t vel)
Overloaded SetSpeed that takes player_pose2d_t as an argument.
Definition: playerc++.h:1844
double MinRight() const
Definition: playerc++.h:1182
Data: calibrated IMU data (PLAYER_IMU_DATA_CALIB)
Definition: player_interfaces.h:4670
uint32_t GetHeight() const
get the height of the image
Definition: playerc++.h:444
uint32_t GetNumHypoths() const
Get the number of localization hypoths.
Definition: playerc++.h:1361
Note: the structure describing the WSN node&#39;s data packet is declared in Player.
Definition: playerc.h:3610
The LimbProxy class is used to control a limb device.
Definition: playerc++.h:1199
player_bbox3d_t GetDeviceSize() const
Return the device size.
Definition: playerc++.h:2232
double GetMaxRange() const
Max range for the latest set of data (meters)
Definition: playerc++.h:1051
The GpsProxy class is used to control a gps device.
Definition: playerc++.h:679
Structure describing a single RFID tag.
Definition: playerc.h:3422
A rectangular bounding box, used to define the origin and bounds of an object.
Definition: player.h:303
int GetIntensity(uint32_t aIndex) const
get the intensity
Definition: playerc++.h:1098
player_orientation_3d_t GetBaseOrientation(void) const
Accessor method for getting the base orientation.
Definition: playerc++.h:193
void GetData(uint8_t *aDest) const
Opaque data.
Definition: playerc++.h:1496
Localization device data.
Definition: playerc.h:2213
Player audio sequence item.
Definition: player_interfaces.h:1484
player_pose3d_t GetSensorPose() const
The pose of the sensor.
Definition: playerc++.h:654
player_audio_mixer_channel_t GetChannel(int aIndex) const
Get Sequence item.
Definition: playerc++.h:291
A color descriptor.
Definition: player.h:316
void SetSpeed(player_pose3d_t vel)
Overloaded SetSpeed that takes player_pose3d_t as input.
Definition: playerc++.h:2023
The Position3dProxy class is used to control a interface_position3d device.
Definition: playerc++.h:1982
Actuator geometry.
Definition: player_interfaces.h:3786
double GetXPos() const
Accessor method.
Definition: playerc++.h:2083
uint32_t GetDefaultOutputChannel() const
Get Default output Channel.
Definition: playerc++.h:266
double GetMaxRange() const
Maximum detectable range of a scan (configured value)
Definition: playerc++.h:2291
void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
simplified version of SetSpeed
Definition: playerc++.h:2014
bool GetStall() const
Accessor method.
Definition: playerc++.h:1972
pointcloud3d proxy data.
Definition: playerc.h:3474
The RangerProxy class is used to control a ranger device.
Definition: playerc++.h:2210
uint32_t GetNumBeams() const
Get the number of breakbeams in the gripper.
Definition: playerc++.h:851
double GetUtmEasting() const
UTM easting and northing (meters).
Definition: playerc++.h:717
Camera proxy data.
Definition: playerc.h:1395
double GetVoltage(uint32_t aIndex) const
Accessor function.
Definition: playerc++.h:226
int GetCellIndex(int x, int y) const
Return the index of the (x,y) item in the cell array.
Definition: playerc++.h:1440
double GetYSpeed() const
Accessor method.
Definition: playerc++.h:1966
The VectorMapProxy class is used to interface to a vectormap.
Definition: playerc++.h:2485
double px
X [m].
Definition: player.h:216
uint32_t GetState(void) const
Get driver state.
Definition: playerc++.h:293
bool GetCharging() const
Returns whether charging is taking place.
Definition: playerc++.h:2152
double GetGa() const
Goal location (radians)
Definition: playerc++.h:1578
void SetSpeed(double aXSpeed, double aYawSpeed)
Same as the previous SetSpeed(), but doesn&#39;t take the yspeed speed (so use this one for non-holonomic...
Definition: playerc++.h:1840
The map proxy provides access to a map device.
Definition: playerc++.h:1419
Simulation device proxy.
Definition: playerc.h:3272
Speech recognition proxy data.
Definition: playerc.h:3384
double GetVel() const
Accessor method.
Definition: playerc++.h:1771
player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const
Get Mixer Detail.
Definition: playerc++.h:264
#define PLAYER_POSITION1D_STATUS_LIMIT_MIN
Status byte: limit min.
Definition: player_interfaces.h:3491
uint32_t GetCapacity() const
Get the capacity of the gripper&#39;s storage.
Definition: playerc++.h:853
double GetWx() const
Current waypoint location (m)
Definition: playerc++.h:1593
double py
Y [m].
Definition: player.h:229
#define PLAYER_POSITION1D_STATUS_LIMIT_MAX
Status byte: limit max.
Definition: player_interfaces.h:3495
double GetVdop() const
Vertical dilution of position (HDOP)
Definition: playerc++.h:714
double GetWatts() const
Returns the watts.
Definition: playerc++.h:2149
double GetConfMinAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition: playerc++.h:1072
A pose in the plane.
Definition: player.h:213
double GetVoltage(uint32_t aIndex) const
get the current voltage
Definition: playerc++.h:1001
uint8_t GetStatus() const
Accessor method.
Definition: playerc++.h:1777
double GetLatitude() const
Latitude and longitude, in degrees.
Definition: playerc++.h:698
bool IsTrajComplete() const
Accessor method.
Definition: playerc++.h:1800
The HealthProxy class is used to get infos of the player-server.
Definition: playerc++.h:871
double GetScanningFrequency() const
Scanning Frequency (Hz)
Definition: playerc++.h:1060
uint32_t GetPathValid() const
Did the planner find a valid path?
Definition: playerc++.h:1544
bool IsLimitMin() const
Accessor method.
Definition: playerc++.h:1780
double GetPa() const
Current pose (radians)
Definition: playerc++.h:1557
Graphics3d device data.
Definition: playerc.h:1685
double GetXSpeed() const
Accessor method.
Definition: playerc++.h:2101
player_bbox2d_t GetFiducialSize() const
The size of the most recently detected fiducial.
Definition: playerc++.h:662
player_point_3d_t GetBasePos(void) const
Accessor method for getting the base position.
Definition: playerc++.h:191
uint32_t GetNumParticles() const
Get the number of particles (for particle filter-based localization systems).
Definition: playerc++.h:1365
uint32_t GetHypothCount() const
Number of possible poses.
Definition: playerc++.h:1344
An angle in 3D space.
Definition: player.h:202
Power device data.
Definition: playerc.h:2880
uint32_t GetWavDataLength() const
Get Wav data length.
Definition: playerc++.h:271
double GetAxes(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:1271
The Pointcloud3d proxy provides an interface to a pointcloud3d device.
Definition: playerc++.h:1656
double GetRangeRes() const
Linear resolution (configured value)
Definition: playerc++.h:2294
void GetImage(uint8_t *aImage) const
Image data This function copies the image data into the data buffer aImage.
Definition: playerc++.h:570
The GripperProxy class is used to control a gripper device.
Definition: playerc++.h:818
The OpaqueProxy proxy provides an interface to a generic opaque.
Definition: playerc++.h:1474
uint32_t GetWaypointCount() const
Number of waypoints in the plan.
Definition: playerc++.h:1641
double GetPercent() const
Returns the percent of power.
Definition: playerc++.h:2143
bool IsEnabled() const
Accessor method.
Definition: playerc++.h:1805
void GoTo(player_pose2d_t pos)
Same as the previous GoTo(), but doesn&#39;t take speed.
Definition: playerc++.h:1864
double GetScanRes() const
Angular resolution of scan (radians)
Definition: playerc++.h:1054
Gripper device data.
Definition: playerc.h:1741
double GetZSpeed() const
Accessor method.
Definition: playerc++.h:2107
The BlackBoardProxy class is used to subscribe to a blackboard device.
Definition: playerc++.h:346
Data: state (PLAYER_LIMB_DATA)
Definition: player_interfaces.h:4037
Structure containing a single actuator&#39;s information.
Definition: player_interfaces.h:3758
Map proxy data.
Definition: playerc.h:2341
uint32_t GetPendingCount() const
Number of pending (unprocessed) sensor readings.
Definition: playerc++.h:1341
Request/reply: get geometry.
Definition: player_interfaces.h:4112
double GetFrequency() const
Scanning frequency (configured value)
Definition: playerc++.h:2297
double GetMinRange() const
Minimum detectable range of a scan (configured value)
Definition: playerc++.h:2288
uint32_t IsBumped(uint32_t aIndex) const
Returns true if the specified bumper has been bumped, false otherwise.
Definition: playerc++.h:489
The Position2dProxy class is used to control a position2d device.
Definition: playerc++.h:1815
double GetXSpeed() const
Accessor method.
Definition: playerc++.h:1963
Position3d device data.
Definition: playerc.h:2776
Info about an available (but not necessarily subscribed) device.
Definition: playerc.h:448
The PtzProxy class is used to control a ptz device.
Definition: playerc++.h:2164
double GetMaxAngle() const
Stop angle of a scan (configured value)
Definition: playerc++.h:2282
A point in the plane.
Definition: player.h:180
int GetCurrentWaypointId() const
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc++.h:1637
double GetJoules() const
Returns the joules.
Definition: playerc++.h:2146
Ranger proxy data.
Definition: playerc.h:3019
bool GetStall() const
Accessor method.
Definition: playerc++.h:1774
double GetMinLeft() const
Minimum range reading on the left side.
Definition: playerc++.h:1170
double GetRange(uint32_t aIndex) const
get the range
Definition: playerc++.h:1089
uint32_t GetCount() const
Number of points in scan.
Definition: playerc++.h:1048
double GetYPos() const
Accessor method.
Definition: playerc++.h:2086
The PlayerClient is used for communicating with the player server.
Definition: playerclient.h:115
double GetCharge() const
Returns the current charge.
Definition: playerc++.h:2140
player_pose2d_t GetGoal() const
Get the goal.
Definition: playerc++.h:1581
bool IsOverCurrent() const
Accessor method.
Definition: playerc++.h:1795
The SpeechProxy class is used to control a speech device.
Definition: playerc++.h:2432
double sw
Width [m].
Definition: player.h:253
double GetWa() const
Current waypoint location (rad)
Definition: playerc++.h:1599
The client proxy base class.
Definition: clientproxy.h:79
double GetMinAngle() const
Start angle of a scan (configured value)
Definition: playerc++.h:2279
player_pose3d_t GetDevicePose() const
Return the device pose.
Definition: playerc++.h:2230
The ImuProxy class is used to control an imu device.
Definition: playerc++.h:931
double px
X [m].
Definition: player.h:227
int GetParticles()
Get the particle set.
Definition: playerc++.h:1351
void SetVelHead(double aXSpeed, double aYawHead)
Same as the previous SetVelHead(), but doesn&#39;t take the yspeed speed (so use this one for non-holonom...
Definition: playerc++.h:1854
double GetTime() const
Time, since the epoch.
Definition: playerc++.h:721
The WiFiProxy class controls a wifi device.
Definition: playerc++.h:2517
double GetYPos() const
Accessor method.
Definition: playerc++.h:1957
uint32_t GetAxesCount() const
Number of valid joystick poses.
Definition: playerc++.h:1278
PTZ device data.
Definition: playerc.h:2937
player_pose2d_t GetPose() const
Get the current pose.
Definition: playerc++.h:1560
double GetZPos() const
Accessor method.
Definition: playerc++.h:2089
double GetGy() const
Goal location (m)
Definition: playerc++.h:1575
double pa
yaw [rad]
Definition: player.h:220
void GoTo(player_pose3d_t aPos)
Same as the previous GoTo(), but does&#39;n take vel argument.
Definition: playerc++.h:2032
Player audio sequence.
Definition: player_interfaces.h:1502
uint32_t GetElementCount() const
Return the individual range sensor count.
Definition: playerc++.h:2227
uint32_t GetWidth() const
get the width of the image
Definition: playerc++.h:442
player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const
Get detected beacon description.
Definition: playerc++.h:650
uint32_t GetChannelCount() const
Get Channel data count.
Definition: playerc++.h:289
double MinLeft() const
Definition: playerc++.h:1178
A rectangular bounding box, used to define the size of an object.
Definition: player.h:241
double GetZoom() const
Return Zoom.
Definition: playerc++.h:2200
player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
Array of possible poses.
Definition: playerc++.h:1347
double GetMinAngle() const
Scan range for the latest set of data (radians)
Definition: playerc++.h:1063
double GetXPos() const
Set PID terms.
Definition: playerc++.h:1954
Speech proxy data.
Definition: playerc.h:3348
Position1d device data.
Definition: playerc.h:2587
double GetRange(uint32_t aIndex) const
get the current range
Definition: playerc++.h:998
player_pose3d_t GetPose() const
get the processed pos of the imu
Definition: playerc++.h:948
The RFIDProxy class is used to control a rfid device.
Definition: playerc++.h:2302
uint32_t GetImageSize() const
Size of the image (bytes)
Definition: playerc++.h:564
uint32_t GetCount() const
How long is the data?
Definition: playerc++.h:1493
uint32_t GetHeight() const
Image dimensions (pixels)
Definition: playerc++.h:553
std::string GetWord(uint32_t aWord) const
Accessor method for getting speech recognition data i.e. words.
Definition: playerc++.h:2469
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1892
GPS proxy data.
Definition: playerc.h:1561
uint32_t GetDefaultInputChannel() const
Get Default input Channel.
Definition: playerc++.h:268
double GetRollSpeed() const
Accessor method.
Definition: playerc++.h:2110
bool IsLimitCen() const
Accessor method.
Definition: playerc++.h:1785
uint32_t GetFormat() const
Image format Possible values include.
Definition: playerc++.h:561
The BumperProxy class is used to read from a bumper device.
Definition: playerc++.h:470
double GetConfMaxAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition: playerc++.h:1074
Audio device data.
Definition: playerc.h:1080
player_pose2d_t GetWaypoint(uint32_t aIndex) const
Get the waypoint.
Definition: playerc++.h:1623
Definition: playerclient.h:90
Sonar proxy data.
Definition: playerc.h:3147
Note: the structure describing the HEALTH&#39;s data packet is declared in Player.
Definition: playerc.h:1824
double GetMinRight() const
Minimum range reading on the right side.
Definition: playerc++.h:1174
player_bbox3d_t GetSensorSize() const
The size of the sensor.
Definition: playerc++.h:658
uint32_t GetMixerDetailsCount() const
Get Mixer Details Count.
Definition: playerc++.h:262
The LinuxjoystickProxy class is used to control a joystick device.
Definition: playerc++.h:1251
void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed, double aYawSpeed)
Send a motor command for a planar robot.
Definition: playerc++.h:2009
uint32_t GetPoseCount() const
Number of valid sonar poses.
Definition: playerc++.h:2411
double GetAngularRes() const
Angular resolution of a scan (configured value)
Definition: playerc++.h:2285
uint32_t GetIntensityCount() const
Return the number of intensity readings.
Definition: playerc++.h:2247
void GoTo(double aX, double aY, double aZ, double aRoll, double aPitch, double aYaw)
Same as the previous GoTo(), but only takes position arguments, no motion speed setting.
Definition: playerc++.h:2038
uint32_t GetTagsCount() const
returns the number of RFID tags
Definition: playerc++.h:2320
double GetYSpeed() const
Accessor method.
Definition: playerc++.h:2104
player_pose3d_t GetPose() const
Get the pose of the gripper.
Definition: playerc++.h:845
uint32_t GetMapSizeX() const
Map dimensions (cells)
Definition: playerc++.h:1321
player_pose3d_t GetRobotPose()
Accessor for the pose of the laser&#39;s parent object (e.g., a robot).
Definition: playerc++.h:1147
The SpeechRecognition proxy provides access to a speech_recognition device.
Definition: playerc++.h:2457
int8_t GetCell(int x, int y) const
Get the (x,y) cell.
Definition: playerc++.h:1444
Blobfinder device data.
Definition: playerc.h:1295
uint32_t GetQuality() const
Fix quality.
Definition: playerc++.h:708
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
The BlinkenlightProxy class is used to enable and disable a flashing indicator light, and to set its period, via a blinkenlight device.
Definition: playerc++.h:419
double pyaw
yaw [rad]
Definition: player.h:237
double sl
Length [m].
Definition: player.h:255
uint32_t GetDepth() const
Image color depth.
Definition: playerc++.h:547
The PowerProxy class controls a power device.
Definition: playerc++.h:2123
Graphics2d device data.
Definition: playerc.h:1625
uint32_t GetButtons() const
return the sensor count
Definition: playerc++.h:1268
player_audio_seq_item_t GetSeqItem(int aIndex) const
Get Sequence item.
Definition: playerc++.h:286
uint32_t GetCount() const
get the number of IR rangers
Definition: playerc++.h:996
uint32_t GetCompression() const
What is the compression type? Currently supported compression types are:
Definition: playerc++.h:581
void SetSpeed(double aXSpeed, double aYawSpeed)
Same as the previous SetSpeed(), but doesn&#39;t take the sideways speed (so use this one for non-holonom...
Definition: playerc++.h:2019
playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
returns a RFID tag
Definition: playerc++.h:2322
double GetPitch() const
Accessor method.
Definition: playerc++.h:2095
uint32_t GetRangeCount() const
Return the number of range readings.
Definition: playerc++.h:2240
The LaserProxy class is used to control a laser device.
Definition: playerc++.h:1026
uint32_t GetCount(void) const
Gets the number of actuators in the array.
Definition: playerc++.h:185
The LogProxy proxy provides access to a log device.
Definition: playerc++.h:1372
The LocalizeProxy class is used to control a localize device, which can provide multiple pose hypothe...
Definition: playerc++.h:1301
int GetType() const
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc++.h:1391
double GetPx() const
Current pose (m)
Definition: playerc++.h:1551
Bumper proxy data.
Definition: playerc.h:1338
Log proxy data.
Definition: playerc.h:2281
double GetYawSpeed() const
Accessor method.
Definition: playerc++.h:2116
uint32_t GetSatellites() const
Number of satellites in view.
Definition: playerc++.h:705
double GetRoll() const
Accessor method.
Definition: playerc++.h:2092
uint32_t GetCount() const
returns the number of blobs
Definition: playerc++.h:436
void GoTo(double aX, double aY, double aYaw)
Same as the previous GoTo(), but only takes position arguments, no motion speed setting.
Definition: playerc++.h:1869
The Graphics3dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition: playerc++.h:781
player_bumper_define_t GetPose(uint32_t aIndex) const
Returns a specific bumper pose.
Definition: playerc++.h:502
double GetPos() const
Set PID terms.
Definition: playerc++.h:1768
double GetYaw() const
Accessor method.
Definition: playerc++.h:1960
playerc_speechrecognition_t * mDevice
libplayerc data structure
Definition: playerc++.h:2463
double GetPan() const
Return Pan (rad)
Definition: playerc++.h:2196
void ResetOdometry()
Reset odometry to 0.
Definition: playerc++.h:1755
Structure describing a single blob.
Definition: player_interfaces.h:1071
double GetGx() const
Goal location (m)
Definition: playerc++.h:1572
bool IntensityOn() const
Whether or not reflectance (i.e., intensity) values are being returned.
Definition: playerc++.h:1077
3D Pointcloud element structure An element as stored in a 3D pointcloud, containing a 3D position plu...
Definition: player_interfaces.h:4798
#define PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE
Status byte: limit trajectory complete.
Definition: player_interfaces.h:3499
player_bbox3d_t GetInnerSize() const
Get the inner size of the gripper.
Definition: playerc++.h:849
Position2d device data.
Definition: playerc.h:2681
Laser proxy data.
Definition: playerc.h:1959
player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:1677
uint32_t GetCount() const
The number of beacons detected.
Definition: playerc++.h:647
joystick proxy data.
Definition: playerc.h:1914
player_pose2d_t GetCurrentWaypoint() const
Get the current waypoint.
Definition: playerc++.h:1602
player_pose3d_t GetPose() const
Accessor for the pose (fill it in by calling RequestGeom)
Definition: playerc++.h:1724
Dio proxy data.
Definition: playerc.h:1461
A pose in space.
Definition: player.h:224
uint32_t GetPoseCount() const
Returns the number bumper poses.
Definition: playerc++.h:499
uint32_t GetDigin() const
A bitfield of the current digital inputs.
Definition: playerc++.h:610
uint32_t GetState() const
Get the gripper state.
Definition: playerc++.h:841
IMU proxy state data.
Definition: playerc.h:3559
double GetHdop() const
Horizontal dilution of position (HDOP)
Definition: playerc++.h:711
bool IsLimitMax() const
Accessor method.
Definition: playerc++.h:1790
uint32_t GetCount() const
Accessor function.
Definition: playerc++.h:223
double GetScan(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:2404
player_pose3d_t GetPose()
Accessor for the pose of the laser with respect to its parent object (e.g., a robot).
Definition: playerc++.h:1134
A point in 3D space.
Definition: player.h:190
Info on a single detected fiducial.
Definition: player_interfaces.h:1688
The Position1dProxy class is used to control a position1d device.
Definition: playerc++.h:1691
void GetMap(int8_t *aMap) const
Occupancy for each cell (empty = -1, unknown = 0, occupied = +1)
Definition: playerc++.h:1461
#define PLAYER_POSITION1D_STATUS_OC
Status byte: limit over current.
Definition: player_interfaces.h:3497
double py
Y [m].
Definition: player.h:218
double GetYawSpeed() const
Accessor method.
Definition: playerc++.h:1969
BlackBoard proxy.
Definition: playerc.h:1178
double GetPy() const
Current pose (m)
Definition: playerc++.h:1554
The AioProxy class is used to read from a aio (analog I/O) device.
Definition: playerc++.h:207
The IrProxy class is used to control an ir device.
Definition: playerc++.h:977
bool GetStall() const
Accessor method.
Definition: playerc++.h:2119
double GetErrHorizontal() const
Errors.
Definition: playerc++.h:724
uint32_t GetSeqCount() const
Get Seq data count.
Definition: playerc++.h:284
player_point_2d_t GetPoint(uint32_t aIndex) const
Scan data (Cartesian): x,y (m)
Definition: playerc++.h:1084
uint32_t GetStored() const
Get the number of currently-stored objects.
Definition: playerc++.h:855
The CameraProxy class can be used to get images from a camera device.
Definition: playerc++.h:517
The WSNProxy class is used to control a wsn device.
Definition: playerc++.h:2585
Player mixer channel detail.
Definition: player_interfaces.h:1555
#define PLAYER_POSITION1D_STATUS_ENABLED
Status byte: enabled.
Definition: player_interfaces.h:3501
The FiducialProxy class is used to control fiducial devices.
Definition: playerc++.h:631
double proll
roll [rad]
Definition: player.h:233
double GetWy() const
Current waypoint location (m)
Definition: playerc++.h:1596
Wifi device proxy.
Definition: playerc.h:3229
double pz
Z [m].
Definition: player.h:231
player_pose3d_t GetOffset()
Accessor for the robot&#39;s pose with respect to its.
Definition: playerc++.h:1881
uint32_t GetCount() const
The number of valid digital inputs.
Definition: playerc++.h:607
uint32_t GetCount() const
return the sensor count
Definition: playerc++.h:2401
The SonarProxy class is used to control a sonar device.
Definition: playerc++.h:2384
double GetTilt() const
Return Tilt (rad)
Definition: playerc++.h:2198
double GetAltitude() const
Altitude, in meters.
Definition: playerc++.h:702
void GetWavData(uint8_t *aData) const
Get Wav data This function copies the wav data into the buffer aImage.
Definition: playerc++.h:276
int GetID() const
get the laser ID, call RequestId first
Definition: playerc++.h:1102
The Graphics2dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition: playerc++.h:735
A line segment, used to construct vector-based maps.
Definition: player.h:287
double GetRangeRes() const
Range resolution of scan (mm)
Definition: playerc++.h:1057
uint32_t GetCount(void) const
Gets the number of words.
Definition: playerc++.h:2475
playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
returns a blob
Definition: playerc++.h:438
uint32_t GetCount() const
return the point count
Definition: playerc++.h:1674
uint32_t GetWidth() const
Image dimensions (pixels)
Definition: playerc++.h:550
The geometry of a single bumper.
Definition: player_interfaces.h:1929
Limb device data.
Definition: playerc.h:2131
double GetMapScale() const
Map scale (m/cell)
Definition: playerc++.h:1329
The DioProxy class is used to read from a dio (digital I/O) device.
Definition: playerc++.h:590
Player mixer channel.
Definition: player_interfaces.h:1516
double GetPitchSpeed() const
Accessor method.
Definition: playerc++.h:2113
uint32_t GetPathDone() const
Have we arrived at the goal?
Definition: playerc++.h:1547
The ActArrayProxy class is used to control a actarray device.
Definition: playerc++.h:141
Player mixer channels.
Definition: player_interfaces.h:1533
enum player_graphics3d_draw_mode player_graphics3d_draw_mode_t
Drawmode: enumeration that defines the drawing mode.
uint32_t GetWidth() const
Map size, in cells.
Definition: playerc++.h:1452
player_bbox3d_t GetSize() const
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1735
Hypothesis format.
Definition: player_interfaces.h:2333
double GetMaxAngle() const
Scan range for the latest set of data (radians)
Definition: playerc++.h:1065
#define PLAYER_POSITION1D_STATUS_LIMIT_CEN
Status byte: limit center.
Definition: player_interfaces.h:3493
Actarray device data.
Definition: playerc.h:986

Last updated 12 September 2005 21:38:45