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., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 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., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 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$
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/signals2.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
92namespace 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
141class 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);
157
160 void RequestGeometry(void);
161
163 void SetPowerConfig(bool aVal);
165 void SetBrakesConfig(bool aVal);
167 void SetSpeedConfig(uint32_t aJoint, float aSpeed);
169 void SetAccelerationConfig(uint32_t aJoint, float aAcc);
170
172 void MoveTo(uint32_t aJoint, float aPos);
174 void MoveToMulti(std::vector<float> aPos);
176 void MoveAtSpeed(uint32_t aJoint, float aSpeed);
178 void MoveAtSpeedMulti(std::vector<float> aSpeed);
180 void MoveHome(int aJoint);
182 void SetActuatorCurrent(uint32_t aJoint, float aCurrent);
184 void SetActuatorCurrentMulti(std::vector<float> aCurrent);
185
187 uint32_t GetCount(void) const { return GetVar(mDevice->actuators_count); }
189 player_actarray_actuator_t GetActuatorData(uint32_t aJoint) const;
191 player_actarray_actuatorgeom_t GetActuatorGeom(uint32_t aJoint) const;
193 player_point_3d_t GetBasePos(void) const { return GetVar(mDevice->base_pos); }
195 player_orientation_3d_t GetBaseOrientation(void) const { return GetVar(mDevice->base_orientation); }
196
197
202 player_actarray_actuator_t operator [](uint32_t aJoint)
203 { return(GetActuatorData(aJoint)); }
204};
205
209class PLAYERCC_EXPORT AioProxy : public ClientProxy
210{
211 private:
212
213 void Subscribe(uint32_t aIndex);
214 void Unsubscribe();
215
216 // libplayerc data structure
217 playerc_aio_t *mDevice;
218
219 public:
220
222 AioProxy (PlayerClient *aPc, uint32_t aIndex=0);
225
227 uint32_t GetCount() const { return(GetVar(mDevice->voltages_count)); };
228
230 double GetVoltage(uint32_t aIndex) const
231 { return(GetVar(mDevice->voltages[aIndex])); };
232
234 void SetVoltage(uint32_t aIndex, double aVoltage);
235
240 double operator [](uint32_t aIndex) const
241 { return GetVoltage(aIndex); }
242
243};
244
245
249class PLAYERCC_EXPORT AudioProxy : public ClientProxy
250{
251
252 private:
253
254 void Subscribe(uint32_t aIndex);
255 void Unsubscribe();
256
257 // libplayerc data structure
258 playerc_audio_t *mDevice;
259
260 public:
261
263 AudioProxy(PlayerClient *aPc, uint32_t aIndex=0);
266
268 uint32_t GetMixerDetailsCount() const {return(GetVar(mDevice->channel_details_list.details_count));};
270 player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const {return(GetVar(mDevice->channel_details_list.details[aIndex]));};
272 uint32_t GetDefaultOutputChannel() const {return(GetVar(mDevice->channel_details_list.default_output));};
274 uint32_t GetDefaultInputChannel() const {return(GetVar(mDevice->channel_details_list.default_input));};
275
277 uint32_t GetWavDataLength() const {return(GetVar(mDevice->wav_data.data_count));};
282 void GetWavData(uint8_t* aData) const
283 {
284 return GetVarByRef(mDevice->wav_data.data,
285 mDevice->wav_data.data+GetWavDataLength(),
286 aData);
287 };
288
290 uint32_t GetSeqCount() const {return(GetVar(mDevice->seq_data.tones_count));};
292 player_audio_seq_item_t GetSeqItem(int aIndex) const {return(GetVar(mDevice->seq_data.tones[aIndex]));};
293
295 uint32_t GetChannelCount() const {return(GetVar(mDevice->mixer_data.channels_count));};
297 player_audio_mixer_channel_t GetChannel(int aIndex) const {return(GetVar(mDevice->mixer_data.channels[aIndex]));};
299 uint32_t GetState(void) const {return(GetVar(mDevice->state));};
300
301
302
304 void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
305
307 void SetWavStremRec(bool aState);
308
310 void PlaySample(int aIndex);
311
313 void PlaySeq(player_audio_seq_t * aTones);
314
316 void SetMultMixerLevels(player_audio_mixer_channel_list_t * aLevels);
317
319 void SetMixerLevel(uint32_t index, float amplitude, uint8_t active);
320
323 void RecordWav();
324
326 void LoadSample(int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
327
330 void GetSample(int aIndex);
331
333 void RecordSample(int aIndex, uint32_t aLength);
334
338
342
343};
344
352class PLAYERCC_EXPORT BlackBoardProxy : public ClientProxy
353{
354 private:
355 void Subscribe(uint32_t aIndex);
356 void Unsubscribe();
357
358 // libplayerc data structure
359 playerc_blackboard_t *mDevice;
360
361 public:
363 BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0);
367 player_blackboard_entry_t *SubscribeToKey(const char *key, const char* group = "");
369 void UnsubscribeFromKey(const char *key, const char* group = "");
371 void SubscribeToGroup(const char* key);
373 void UnsubscribeFromGroup(const char* group);
377 player_blackboard_entry_t *GetEntry(const char* key, const char* group);
380};
381
382// /**
383// The @p BlinkenlightProxy class is used to enable and disable
384// a flashing indicator light, and to set its period, via a @ref
385// interface_blinkenlight device */
386// class PLAYERCC_EXPORT BlinkenLightProxy : public ClientProxy
387// {
388// private:
389//
390// void Subscribe(uint32_t aIndex);
391// void Unsubscribe();
392//
393// // libplayerc data structure
394// playerc_blinkenlight_t *mDevice;
395//
396// public:
397// /** Constructor.
398// Leave the access field empty to start unconnected.
399// */
400// BlinkenLightProxy(PlayerClient *aPc, uint32_t aIndex=0);
401// ~BlinkenLightProxy();
402//
403// // true: indicator light enabled, false: disabled.
404// bool GetEnable();
405//
406// /** The current period (one whole on/off cycle) of the blinking
407// light. If the period is zero and the light is enabled, the light
408// is on.
409// */
410// void SetPeriod(double aPeriod);
411//
412// /** Set the state of the indicator light. A period of zero means
413// the light will be unblinkingly on or off. Returns 0 on
414// success, else -1.
415// */
416// void SetEnable(bool aSet);
417// };
418
425class PLAYERCC_EXPORT BlobfinderProxy : public ClientProxy
426{
427 private:
428
429 void Subscribe(uint32_t aIndex);
430 void Unsubscribe();
431
432 // libplayerc data structure
433 playerc_blobfinder_t *mDevice;
434
435 public:
437 BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0);
440
442 uint32_t GetCount() const { return GetVar(mDevice->blobs_count); };
444 playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
445 { return GetVar(mDevice->blobs[aIndex]);};
446
448 uint32_t GetWidth() const { return GetVar(mDevice->width); };
450 uint32_t GetHeight() const { return GetVar(mDevice->height); };
451
456 playerc_blobfinder_blob_t operator [](uint32_t aIndex) const
457 { return(GetBlob(aIndex)); }
458
459/*
460 // Set the color to be tracked
461 void SetTrackingColor(uint32_t aReMin=0, uint32_t aReMax=255, uint32_t aGrMin=0,
462 uint32_t aGrMax=255, uint32_t aBlMin=0, uint32_t aBlMax=255);
463 void SetImagerParams(int aContrast, int aBrightness,
464 int aAutogain, int aColormode);
465 void SetContrast(int aC);
466 void SetColorMode(int aM);
467 void SetBrightness(int aB);
468 void SetAutoGain(int aG);*/
469
470};
471
476class PLAYERCC_EXPORT BumperProxy : public ClientProxy
477{
478
479 private:
480
481 void Subscribe(uint32_t aIndex);
482 void Unsubscribe();
483
484 // libplayerc data structure
485 playerc_bumper_t *mDevice;
486
487 public:
488
490 BumperProxy(PlayerClient *aPc, uint32_t aIndex=0);
493
495 uint32_t GetCount() const { return GetVar(mDevice->bumper_count); };
496
498 uint32_t IsBumped(uint32_t aIndex) const
499 { return GetVar(mDevice->bumpers[aIndex]); };
500
503
506
508 uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
509
511 player_bumper_define_t GetPose(uint32_t aIndex) const
512 { return GetVar(mDevice->poses[aIndex]); };
513
518 bool operator [](uint32_t aIndex) const
519 { return IsBumped(aIndex) != 0 ? true : false; }
520
521};
522
526class PLAYERCC_EXPORT CameraProxy : public ClientProxy
527{
528
529 private:
530
531 virtual void Subscribe(uint32_t aIndex);
532 virtual void Unsubscribe();
533
534 // libplayerc data structure
535 playerc_camera_t *mDevice;
536
537 std::string mPrefix;
538 int mFrameNo;
539
540 public:
541
543 CameraProxy (PlayerClient *aPc, uint32_t aIndex=0);
544
546 virtual ~CameraProxy();
547
551 void SaveFrame(const std::string aPrefix, uint32_t aWidth=4);
552
555
557 uint32_t GetDepth() const { return GetVar(mDevice->bpp); };
558
560 uint32_t GetWidth() const { return GetVar(mDevice->width); };
561
563 uint32_t GetHeight() const { return GetVar(mDevice->height); };
564
571 uint32_t GetFormat() const { return GetVar(mDevice->format); };
572
574 uint32_t GetImageSize() const { return GetVar(mDevice->image_count); };
575
580 void GetImage(uint8_t* aImage) const
581 {
582 return GetVarByRef(mDevice->image,
583 mDevice->image+GetVar(mDevice->image_count),
584 aImage);
585 };
586
591 uint32_t GetCompression() const { return GetVar(mDevice->compression); };
592
593};
594
598class PLAYERCC_EXPORT CoopObjectProxy : public ClientProxy
599{
600
601 private:
602
603 void Subscribe(uint32_t aIndex);
604 void Unsubscribe();
605
606 // libplayerc data structure
607 playerc_coopobject_t *mDevice;
608
609 uint16_t id;
610
611 public:
613 CoopObjectProxy(PlayerClient *aPc, uint32_t aIndex = 0);
616
628 int MessageType () const { return GetVar(mDevice->messageType); };
629
636 uint32_t GetOrigin () const { return GetVar(mDevice->origin); };
637
639 uint32_t GetID () const { return GetVar(mDevice->id); };
640
642 uint32_t GetParentID() const { return GetVar(mDevice->parent_id); };
643
645 uint32_t GetProxyID () const { return id; };
646
648 void SetProxyID (uint32_t value) { id = value; };
649
651 uint32_t GetSensorNumber () const { return GetVar(mDevice->sensor_data_count); };
652
653 // int *GetAllSensorData () const { return GetVar(mDevice->sensor_data); };
654
672 uint8_t GetSensorType (uint32_t index) const { if ( index < GetSensorNumber() ) return GetVar(mDevice->sensor_data[index].type); else return -1; };
673
675 uint16_t GetSensorData (uint32_t index) const { if ( index < GetSensorNumber() ) return GetVar(mDevice->sensor_data[index].value); else return -1; };
676
678 uint32_t GetAlarmNumber () const { return GetVar(mDevice->alarm_data_count); };
679
680// int *GetAllAlarmData () const { return GetVar(mDevice->alarm_data); };
681
701 uint8_t GetAlarmType (uint32_t index) const { if ( index < GetAlarmNumber() ) return GetVar(mDevice->alarm_data[index].type); else return -1; };
702
704 uint16_t GetAlarmData (uint32_t index) const { if ( index < GetAlarmNumber() ) return GetVar(mDevice->alarm_data[index].value); else return -1; };
705
707 uint32_t GetUserDataNumber () const { return GetVar(mDevice->user_data_count); };
708
710 uint8_t *GetAllUserData () const { return GetVar(mDevice->user_data); };
711
713 uint8_t GetUserData (uint32_t index) const { if ( index < GetUserDataNumber() ) return GetVar(mDevice->user_data[index]); else return 0xFF; };
714
716 uint16_t GetRSSIsenderId () const { return GetVar(mDevice->RSSIsender); };
718 uint16_t GetRSSIvalue () const { return GetVar(mDevice->RSSIvalue); };
720 uint16_t GetRSSIstamp () const { return GetVar(mDevice->RSSIstamp); };
722 double GetRSSInodeTime () const { return (double)(mDevice->RSSInodeTimeHigh + 10e-6*mDevice->RSSInodeTimeLow); };
723
725 float GetX () const { return GetVar(mDevice->x); };
727 float GetY () const { return GetVar(mDevice->y); };
729 float GetZ () const { return GetVar(mDevice->z); };
731 uint8_t GetStatus () const { return GetVar(mDevice->status); };
732
734 uint32_t GetRequest () const { return GetVar(mDevice->request); };
736 uint32_t GetCommand () const { return GetVar(mDevice->command); };
738 uint32_t GetParametersSize () const { return GetVar(mDevice->parameters_count); };
740 uint8_t *GetAllParameters () const { return GetVar(mDevice->parameters); };
742 uint8_t GetParameter (uint32_t index) const { if ( index < GetParametersSize() ) return GetVar(mDevice->parameters[index]); else return 0xFF; };
743
745 void SendData(int destID, int sourceID, player_pose2d_t pos, int status);
747 void SendData(int destID, int sourceID, int extradata_type, uint32_t extradata_size, uint8_t *extradata);
749 void SendCommand(int destID, int sourceID, int command, uint32_t cmd_parameters_size = 0, uint8_t *cmd_parameters = NULL);
751 void SendRequest(int destID, int sourceID, int request, uint32_t req_parameters_size = 0, uint8_t *req_parameters = NULL);
752
753
754};
755
765class PLAYERCC_EXPORT DioProxy : public ClientProxy
766{
767 private:
768
769 void Subscribe(uint32_t aIndex);
770 void Unsubscribe();
771
772 // libplayerc data structure
773 playerc_dio_t *mDevice;
774
775 public:
777 DioProxy(PlayerClient *aPc, uint32_t aIndex=0);
780
782 uint32_t GetCount() const { return GetVar(mDevice->count); };
783
785 uint32_t GetDigin() const { return GetVar(mDevice->digin); };
786
788 bool GetInput(uint32_t aIndex) const;
789
791 void SetOutput(uint32_t aCount, uint32_t aDigout);
792
797 uint32_t operator [](uint32_t aIndex) const
798 { return GetInput(aIndex); }
799};
800
806class PLAYERCC_EXPORT FiducialProxy : public ClientProxy
807{
808 private:
809 void Subscribe(uint32_t aIndex);
810 void Unsubscribe();
811
812 // libplayerc data structure
813 playerc_fiducial_t *mDevice;
814
815 public:
817 FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0);
820
822 uint32_t GetCount() const { return GetVar(mDevice->fiducials_count); };
823
825 player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const
826 { return GetVar(mDevice->fiducials[aIndex]);};
827
830 { return GetVar(mDevice->fiducial_geom.pose);};
831
834 { return GetVar(mDevice->fiducial_geom.size);};
835
838 { return GetVar(mDevice->fiducial_geom.fiducial_size);};
839
842
847 player_fiducial_item_t operator [](uint32_t aIndex) const
848 { return GetFiducialItem(aIndex); }
849};
850
854class PLAYERCC_EXPORT GpsProxy : public ClientProxy
855{
856
857 private:
858
859 void Subscribe(uint32_t aIndex);
860 void Unsubscribe();
861
862 // libplayerc data structure
863 playerc_gps_t *mDevice;
864
865 public:
866
868 GpsProxy(PlayerClient *aPc, uint32_t aIndex=0);
871
873 double GetLatitude() const { return GetVar(mDevice->lat); };
874 double GetLongitude() const { return GetVar(mDevice->lon); };
875
877 double GetAltitude() const { return GetVar(mDevice->alt); };
878
880 double GetSpeed() const { return GetVar(mDevice->speed); };
881
884 double GetCourse() const { return GetVar(mDevice->course); };
885
887 uint32_t GetSatellites() const { return GetVar(mDevice->sat_count); };
888
890 uint32_t GetQuality() const { return GetVar(mDevice->quality); };
891
893 double GetHdop() const { return GetVar(mDevice->hdop); };
894
896 double GetVdop() const { return GetVar(mDevice->vdop); };
897
899 double GetUtmEasting() const { return GetVar(mDevice->utm_e); };
900 double GetUtmNorthing() const { return GetVar(mDevice->utm_n); };
901
903 double GetTime() const { return GetVar(mDevice->utc_time); };
904
906 double GetErrHorizontal() const { return GetVar(mDevice->err_horz); };
907 double GetErrVertical() const { return GetVar(mDevice->err_vert); };
908};
909
917class PLAYERCC_EXPORT Graphics2dProxy : public ClientProxy
918{
919
920 private:
921
922 // Subscribe
923 void Subscribe(uint32_t aIndex);
924 // Unsubscribe
925 void Unsubscribe();
926
927 // libplayerc data structure
928 playerc_graphics2d_t *mDevice;
929
930 public:
932 Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
935
938
940 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
941
943 void Clear(void);
944
946 void DrawPoints(player_point_2d_t pts[], int count);
947
950 int count,
951 bool filled,
952 player_color_t fill_color);
953
955 void DrawPolyline(player_point_2d_t pts[], int count);
956
957
959 void DrawMultiline(player_point_2d_t pts[], int count);
960};
961
967class PLAYERCC_EXPORT Graphics3dProxy : public ClientProxy
968{
969
970 private:
971
972 // Subscribe
973 void Subscribe(uint32_t aIndex);
974 // Unsubscribe
975 void Unsubscribe();
976
977 // libplayerc data structure
978 playerc_graphics3d_t *mDevice;
979
980 public:
982 Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
985
988
990 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
991
993 void Clear(void);
994
996 void Draw(player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count);
997
998};
999
1004class PLAYERCC_EXPORT GripperProxy : public ClientProxy
1005{
1006
1007 private:
1008
1009 void Subscribe(uint32_t aIndex);
1010 void Unsubscribe();
1011
1012 // libplayerc data structure
1013 playerc_gripper_t *mDevice;
1014
1015 public:
1016
1018 GripperProxy(PlayerClient *aPc, uint32_t aIndex=0);
1021
1025
1027 uint32_t GetState() const { return GetVar(mDevice->state); };
1029 uint32_t GetBeams() const { return GetVar(mDevice->beams); };
1031 player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
1033 player_bbox3d_t GetOuterSize() const { return GetVar(mDevice->outer_size); };
1035 player_bbox3d_t GetInnerSize() const { return GetVar(mDevice->inner_size); };
1037 uint32_t GetNumBeams() const { return GetVar(mDevice->num_beams); };
1039 uint32_t GetCapacity() const { return GetVar(mDevice->capacity); };
1041 uint32_t GetStored() const { return GetVar(mDevice->stored); };
1042
1044 void Open();
1046 void Close();
1048 void Stop();
1050 void Store();
1052 void Retrieve();
1053};
1054
1057class PLAYERCC_EXPORT HealthProxy : public ClientProxy
1058{
1059
1060 private:
1061
1062 void Subscribe(uint32_t aIndex);
1063 void Unsubscribe();
1064
1065 // libplayerc data structure
1066 playerc_health_t *mDevice;
1067
1068 public:
1070 HealthProxy(PlayerClient *aPc, uint32_t aIndex=0);
1073
1075 float GetIdleCPU();
1076
1079
1081 float GetUserCPU();
1082
1084 int64_t GetMemTotal();
1085
1087 int64_t GetMemUsed();
1088
1090 int64_t GetMemFree();
1091
1093 int64_t GetSwapTotal();
1094
1096 int64_t GetSwapUsed();
1097
1099 int64_t GetSwapFree();
1100
1103
1106
1109};
1110
1111
1112
1117class PLAYERCC_EXPORT ImuProxy : public ClientProxy
1118{
1119 private:
1120 void Subscribe(uint32_t aIndex);
1121 void Unsubscribe();
1122
1123 // libplayerc data structure
1124 playerc_imu_t *mDevice;
1125
1126 public:
1127
1129 ImuProxy(PlayerClient *aPc, uint32_t aIndex=0);
1132
1134 player_pose3d_t GetPose() const { return GetVar(mDevice->pose); };
1135
1137 float GetXAccel();
1139 float GetYAccel();
1141 float GetZAccel();
1143 float GetXGyro();
1145 float GetYGyro();
1147 float GetZGyro();
1149 float GetXMagn();
1151 float GetYMagn();
1153 float GetZMagn();
1154
1156 player_imu_data_calib_t GetRawValues() const
1157 { return GetVar(mDevice->calib_data); };
1158
1160 void SetDatatype(int aDatatype);
1161
1163 void ResetOrientation(int aValue);
1164
1166 void ResetEuler(float aRoll, float aPitch, float aYaw);
1167
1168};
1169
1170
1175class PLAYERCC_EXPORT IrProxy : public ClientProxy
1176{
1177
1178 private:
1179
1180 void Subscribe(uint32_t aIndex);
1181 void Unsubscribe();
1182
1183 // libplayerc data structure
1184 playerc_ir_t *mDevice;
1185
1186 public:
1187
1189 IrProxy(PlayerClient *aPc, uint32_t aIndex=0);
1192
1194 uint32_t GetCount() const { return GetVar(mDevice->data.ranges_count); };
1196 double GetRange(uint32_t aIndex) const
1197 { return GetVar(mDevice->data.ranges[aIndex]); };
1199 double GetVoltage(uint32_t aIndex) const
1200 { return GetVar(mDevice->data.voltages[aIndex]); };
1202 uint32_t GetPoseCount() const { return GetVar(mDevice->poses.poses_count); };
1204 player_pose3d_t GetPose(uint32_t aIndex) const
1205 {return GetVar(mDevice->poses.poses[aIndex]);};
1206
1209
1214 double operator [](uint32_t aIndex) const
1215 { return GetRange(aIndex); }
1216
1217};
1218
1224class PLAYERCC_EXPORT LaserProxy : public ClientProxy
1225{
1226 private:
1227
1228 void Subscribe(uint32_t aIndex);
1229 void Unsubscribe();
1230
1231 // libplayerc data structure
1232 playerc_laser_t *mDevice;
1233
1234 // local storage of config
1235 double min_angle, max_angle, scan_res, range_res, scanning_frequency;
1236 bool intensity;
1237
1238 public:
1239
1241 LaserProxy(PlayerClient *aPc, uint32_t aIndex=0);
1244
1246 uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
1247
1249 double GetMaxRange() const { return GetVar(mDevice->max_range); };
1250
1252 double GetScanRes() const { return GetVar(mDevice->scan_res); };
1253
1255 double GetRangeRes() const { return GetVar(mDevice->range_res); };
1256
1258 double GetScanningFrequency() const { return GetVar(mDevice->scanning_frequency); };
1259
1261 double GetMinAngle() const { return GetVar(mDevice->scan_start); };
1263 double GetMaxAngle() const
1264 {
1265 scoped_lock_t lock(mPc->mMutex);
1266 return mDevice->scan_start + (mDevice->scan_count - 1)*mDevice->scan_res;
1267 };
1268
1270 double GetConfMinAngle() const { return min_angle; };
1272 double GetConfMaxAngle() const { return max_angle; };
1273
1275 bool IntensityOn() const { return GetVar(mDevice->intensity_on) != 0 ? true : false; };
1276
1277// // Scan data (polar): range (m) and bearing (radians)
1278// double GetScan(uint32_t aIndex) const
1279// { return GetVar(mDevice->scan[aIndex]); };
1280
1282 player_point_2d_t GetPoint(uint32_t aIndex) const
1283 { return GetVar(mDevice->point[aIndex]); };
1284
1285
1287 double GetRange(uint32_t aIndex) const
1288 { return GetVar(mDevice->ranges[aIndex]); };
1289
1291 double GetBearing(uint32_t aIndex) const
1292 { return GetVar(mDevice->scan[aIndex][1]); };
1293
1294
1296 int GetIntensity(uint32_t aIndex) const
1297 { return GetVar(mDevice->intensity[aIndex]); };
1298
1300 int GetID() const
1301 { return GetVar(mDevice->laser_id); };
1302
1303
1312 void Configure(double aMinAngle,
1313 double aMaxAngle,
1314 uint32_t aScanRes,
1315 uint32_t aRangeRes,
1316 bool aIntensity,
1317 double aScanningFrequency);
1318
1322
1325
1329
1333 {
1335 scoped_lock_t lock(mPc->mMutex);
1336
1337 p.px = mDevice->pose[0];
1338 p.py = mDevice->pose[1];
1339 p.pyaw = mDevice->pose[2];
1340 return(p);
1341 }
1342
1346 {
1348 scoped_lock_t lock(mPc->mMutex);
1349
1350 p.px = mDevice->robot_pose[0];
1351 p.py = mDevice->robot_pose[1];
1352 p.pyaw = mDevice->robot_pose[2];
1353 return(p);
1354 }
1355
1358 {
1360 scoped_lock_t lock(mPc->mMutex);
1361
1362 b.sl = mDevice->size[0];
1363 b.sw = mDevice->size[1];
1364 return(b);
1365 }
1366
1368 double GetMinLeft() const
1369 { return GetVar(mDevice->min_left); };
1370
1372 double GetMinRight() const
1373 { return GetVar(mDevice->min_right); };
1374
1376 double MinLeft () const
1377 { return GetMinLeft(); }
1378
1380 double MinRight () const
1381 { return GetMinRight(); }
1382
1387 double operator [] (uint32_t index) const
1388 { return GetRange(index);}
1389
1390};
1391
1392
1397class PLAYERCC_EXPORT LimbProxy : public ClientProxy
1398{
1399 private:
1400
1401 void Subscribe(uint32_t aIndex);
1402 void Unsubscribe();
1403
1404 // libplayerc data structure
1405 playerc_limb_t *mDevice;
1406
1407 public:
1408
1410 LimbProxy(PlayerClient *aPc, uint32_t aIndex=0);
1413
1417
1419 void SetPowerConfig(bool aVal);
1421 void SetBrakesConfig(bool aVal);
1423 void SetSpeedConfig(float aSpeed);
1424
1426 void MoveHome(void);
1428 void Stop(void);
1430 void SetPose(float aPX, float aPY, float aPZ,
1431 float aAX, float aAY, float aAZ,
1432 float aOX, float aOY, float aOZ);
1434 void SetPosition(float aX, float aY, float aZ);
1437 void VectorMove(float aX, float aY, float aZ, float aLength);
1438
1440 player_limb_data_t GetData(void) const;
1442 player_limb_geom_req_t GetGeom(void) const;
1443};
1444
1445
1451class PLAYERCC_EXPORT LinuxjoystickProxy : public ClientProxy
1452{
1453 private:
1454
1455 void Subscribe(uint32_t aIndex);
1456 void Unsubscribe();
1457
1458 // libplayerc data structure
1459 playerc_joystick_t *mDevice;
1460
1461 public:
1462 // Constructor
1463 LinuxjoystickProxy(PlayerClient *aPc, uint32_t aIndex=0);
1464 // Destructor
1466
1468 uint32_t GetButtons() const { return GetVar(mDevice->buttons); };
1469
1471 double GetAxes(uint32_t aIndex) const
1472 { if (GetVar(mDevice->axes_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->pos[aIndex]); };
1475 double operator [] (uint32_t aIndex) const { return GetAxes(aIndex); }
1476
1478 uint32_t GetAxesCount() const { return GetVar(mDevice->axes_count); };
1479
1481// player_pose3d_t GetPose(uint32_t aIndex) const
1482// { return GetVar(mDevice->poses[aIndex]); };
1483
1484 // Enable/disable the joysticks.
1485 // Set @p state to 1 to enable, 0 to disable.
1486 // Note that when joysticks are disabled the client will still receive joystick
1487 // data, but the ranges will always be the last value read from the joysticks
1488 // before they were disabled.
1489 //void SetEnable(bool aEnable);
1490
1492// void RequestGeom();
1493};
1494
1495
1501class PLAYERCC_EXPORT LocalizeProxy : public ClientProxy
1502{
1503
1504 private:
1505
1506 void Subscribe(uint32_t aIndex);
1507 void Unsubscribe();
1508
1509 // libplayerc data structure
1510 playerc_localize_t *mDevice;
1511
1512 public:
1513
1515 LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0);
1518
1520 // @todo should these be in a player_pose_t?
1521 uint32_t GetMapSizeX() const { return GetVar(mDevice->map_size_x); };
1523 uint32_t GetMapSizeY() const { return GetVar(mDevice->map_size_y); };
1524
1525 // @todo should these be in a player_pose_t?
1527 uint32_t GetMapTileX() const { return GetVar(mDevice->map_tile_x); };
1529 uint32_t GetMapTileY() const { return GetVar(mDevice->map_tile_y); };
1530
1532 double GetMapScale() const { return GetVar(mDevice->map_scale); };
1533
1534 // Map data (empty = -1, unknown = 0, occupied = +1)
1535 // is this still needed? if so,
1536 //void GetMapCells(uint8_t* aCells) const
1537 //{
1538 // return GetVarByRef(mDevice->map_cells,
1539 // mDevice->image+GetVar(mDevice->??map_cell_cout??),
1540 // aCells);
1541 //};
1542
1544 uint32_t GetPendingCount() const { return GetVar(mDevice->pending_count); };
1545
1547 uint32_t GetHypothCount() const { return GetVar(mDevice->hypoth_count); };
1548
1550 player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
1551 { return GetVar(mDevice->hypoths[aIndex]); };
1552
1555 { return playerc_localize_get_particles(mDevice); }
1556
1559
1561 void SetPose(double pose[3], double cov[6]);
1562
1564 uint32_t GetNumHypoths() const { return GetVar(mDevice->hypoth_count); };
1565
1568 uint32_t GetNumParticles() const { return GetVar(mDevice->num_particles); };
1569};
1570
1571
1575class PLAYERCC_EXPORT LogProxy : public ClientProxy
1576{
1577 private:
1578
1579 void Subscribe(uint32_t aIndex);
1580 void Unsubscribe();
1581
1582 // libplayerc data structure
1583 playerc_log_t *mDevice;
1584
1585 public:
1587 LogProxy(PlayerClient *aPc, uint32_t aIndex=0);
1588
1591
1594 int GetType() const { return GetVar(mDevice->type); };
1595
1597 int GetState() const { return GetVar(mDevice->state); };
1598
1601
1604 void SetState(int aState);
1605
1607 void SetWriteState(int aState);
1608
1610 void SetReadState(int aState);
1611
1613 void Rewind();
1614
1616 void SetFilename(const std::string aFilename);
1617};
1618
1622class PLAYERCC_EXPORT MapProxy : public ClientProxy
1623{
1624 private:
1625
1626 void Subscribe(uint32_t aIndex);
1627 void Unsubscribe();
1628
1629 // libplayerc data structure
1630 playerc_map_t *mDevice;
1631
1632 public:
1634 MapProxy(PlayerClient *aPc, uint32_t aIndex=0);
1635
1638
1641
1643 int GetCellIndex(int x, int y) const
1644 { return y*GetWidth() + x; };
1645
1647 int8_t GetCell(int x, int y) const
1648 { return GetVar(mDevice->cells[GetCellIndex(x,y)]); };
1649
1651 double GetResolution() const { return GetVar(mDevice->resolution); };
1652
1654 // @todo should this be returned as a player_size_t?
1655 uint32_t GetWidth() const { return GetVar(mDevice->width); };
1657 // @todo should this be returned as a player_size_t?
1658 uint32_t GetHeight() const { return GetVar(mDevice->height); };
1659
1660 double GetOriginX() const { return GetVar(mDevice->origin[0]); };
1661 double GetOriginY() const { return GetVar(mDevice->origin[1]); };
1662
1664 int8_t GetDataRange() const { return GetVar(mDevice->data_range); };
1665
1667 void GetMap(int8_t* aMap) const
1668 {
1669 return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->cells),
1670 reinterpret_cast<int8_t*>(mDevice->cells+GetWidth()*GetHeight()),
1671 aMap);
1672 };
1673};
1674
1680class PLAYERCC_EXPORT OpaqueProxy : public ClientProxy
1681{
1682
1683 private:
1684
1685 void Subscribe(uint32_t aIndex);
1686 void Unsubscribe();
1687
1688 // libplayerc data structure
1689 playerc_opaque_t *mDevice;
1690
1691 public:
1692
1694 OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0);
1697
1699 uint32_t GetCount() const { return GetVar(mDevice->data_count); };
1700
1702 void GetData(uint8_t* aDest) const
1703 {
1704 return GetVarByRef(mDevice->data,
1705 mDevice->data+GetVar(mDevice->data_count),
1706 aDest);
1707 };
1708
1710 void SendCmd(player_opaque_data_t* aData);
1711
1713 int SendReq(player_opaque_data_t* aRequest);
1714
1715};
1716
1720class PLAYERCC_EXPORT PlannerProxy : public ClientProxy
1721{
1722
1723 private:
1724
1725 void Subscribe(uint32_t aIndex);
1726 void Unsubscribe();
1727
1728 // libplayerc data structure
1729 playerc_planner_t *mDevice;
1730
1731 public:
1732
1734 PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0);
1737
1739 void SetGoalPose(double aGx, double aGy, double aGa);
1740
1742 void SetStartPose(double aSx, double aSy, double aSa);
1743
1747
1750 void SetEnable(bool aEnable);
1751
1753 uint32_t GetPathValid() const { return GetVar(mDevice->path_valid); };
1754
1756 uint32_t GetPathDone() const { return GetVar(mDevice->path_done); };
1757
1760 double GetPathLength() const {return GetVar(mDevice->waypoint_distance); };
1761
1764 double GetPx() const { return GetVar(mDevice->px); };
1767 double GetPy() const { return GetVar(mDevice->py); };
1770 double GetPa() const { return GetVar(mDevice->pa); };
1771
1774 {
1776 scoped_lock_t lock(mPc->mMutex);
1777 p.px = mDevice->px;
1778 p.py = mDevice->py;
1779 p.pa = mDevice->pa;
1780 return(p);
1781 }
1782
1785 double GetGx() const { return GetVar(mDevice->gx); };
1788 double GetGy() const { return GetVar(mDevice->gy); };
1791 double GetGa() const { return GetVar(mDevice->ga); };
1792
1795 {
1797 scoped_lock_t lock(mPc->mMutex);
1798 p.px = mDevice->gx;
1799 p.py = mDevice->gy;
1800 p.pa = mDevice->ga;
1801 return(p);
1802 }
1803
1806 double GetWx() const { return GetVar(mDevice->wx); };
1809 double GetWy() const { return GetVar(mDevice->wy); };
1812 double GetWa() const { return GetVar(mDevice->wa); };
1813
1816 {
1818 scoped_lock_t lock(mPc->mMutex);
1819 p.px = mDevice->wx;
1820 p.py = mDevice->wy;
1821 p.pa = mDevice->wa;
1822 return(p);
1823 }
1824
1827 double GetIx(int i) const;
1830 double GetIy(int i) const;
1833 double GetIa(int i) const;
1834
1836 player_pose2d_t GetWaypoint(uint32_t aIndex) const
1837 {
1838 assert(aIndex < GetWaypointCount());
1840 scoped_lock_t lock(mPc->mMutex);
1841 p.px = mDevice->waypoints[aIndex][0];
1842 p.py = mDevice->waypoints[aIndex][1];
1843 p.pa = mDevice->waypoints[aIndex][2];
1844 return(p);
1845 }
1846
1851 { return GetVar(mDevice->curr_waypoint); };
1852
1854 uint32_t GetWaypointCount() const
1855 { return GetVar(mDevice->waypoint_count); };
1856
1861 player_pose2d_t operator [](uint32_t aIndex) const
1862 { return GetWaypoint(aIndex); }
1863
1864};
1865
1869class PLAYERCC_EXPORT Pointcloud3dProxy : public ClientProxy
1870{
1871 private:
1872
1873 void Subscribe(uint32_t aIndex);
1874 void Unsubscribe();
1875
1876 // libplayerc data structure
1877 playerc_pointcloud3d_t *mDevice;
1878
1879 public:
1881 Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1882
1885
1887 uint32_t GetCount() const { return GetVar(mDevice->points_count); };
1888
1890 player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const
1891 { return GetVar(mDevice->points[aIndex]); };
1892
1895 player_pointcloud3d_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); }
1896
1897};
1898
1899
1904class PLAYERCC_EXPORT Position1dProxy : public ClientProxy
1905{
1906
1907 private:
1908
1909 void Subscribe(uint32_t aIndex);
1910 void Unsubscribe();
1911
1912 // libplayerc data structure
1913 playerc_position1d_t *mDevice;
1914
1915 public:
1916
1918 Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1921
1925 void SetSpeed(double aVel);
1926
1930 void GoTo(double aPos, double aVel);
1931
1935
1938 {
1940 scoped_lock_t lock(mPc->mMutex);
1941 p.px = mDevice->pose[0];
1942 p.py = mDevice->pose[1];
1943 p.pyaw = mDevice->pose[2];
1944 return(p);
1945 }
1946
1949 {
1951 scoped_lock_t lock(mPc->mMutex);
1952 b.sl = mDevice->size[0];
1953 b.sw = mDevice->size[1];
1954 return(b);
1955 }
1956
1961 void SetMotorEnable(bool enable);
1962
1965 void SetOdometry(double aPos);
1966
1968 void ResetOdometry() { SetOdometry(0); };
1969
1970 // Set PID terms
1971 //void SetSpeedPID(double kp, double ki, double kd);
1972
1973 // Set PID terms
1974 //void SetPositionPID(double kp, double ki, double kd);
1975
1976 // Set speed ramping profile
1977 // spd rad/s, acc rad/s/s
1978 //void SetPositionSpeedProfile(double spd, double acc);
1979
1981 double GetPos() const { return GetVar(mDevice->pos); };
1982
1984 double GetVel() const { return GetVar(mDevice->vel); };
1985
1987 bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
1988
1990 uint8_t GetStatus() const { return GetVar(mDevice->status); };
1991
1993 bool IsLimitMin() const
1994 { return (GetVar(mDevice->status) &
1995 (1 << PLAYER_POSITION1D_STATUS_LIMIT_MIN)) > 0; };
1996
1998 bool IsLimitCen() const
1999 { return (GetVar(mDevice->status) &
2000 (1 << PLAYER_POSITION1D_STATUS_LIMIT_CEN)) > 0; };
2001
2003 bool IsLimitMax() const
2004 { return (GetVar(mDevice->status) &
2005 (1 << PLAYER_POSITION1D_STATUS_LIMIT_MAX)) > 0; };
2006
2008 bool IsOverCurrent() const
2009 { return (GetVar(mDevice->status) &
2010 (1 << PLAYER_POSITION1D_STATUS_OC)) > 0; };
2011
2013 bool IsTrajComplete() const
2014 { return (GetVar(mDevice->status) &
2015 (1 << PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE)) > 0; };
2016
2018 bool IsEnabled() const
2019 { return (GetVar(mDevice->status) &
2020 (1 << PLAYER_POSITION1D_STATUS_ENABLED)) > 0; };
2021
2022};
2023
2028class PLAYERCC_EXPORT Position2dProxy : public ClientProxy
2029{
2030
2031 private:
2032
2033 void Subscribe(uint32_t aIndex);
2034 void Unsubscribe();
2035
2036 // libplayerc data structure
2037 playerc_position2d_t *mDevice;
2038
2039 public:
2040
2042 Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
2045
2049 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed);
2050
2053 void SetSpeed(double aXSpeed, double aYawSpeed)
2054 { return SetSpeed(aXSpeed, 0, aYawSpeed);}
2055
2058 { return SetSpeed(vel.px, vel.py, vel.pa);}
2059
2063 void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead);
2064
2067 void SetVelHead(double aXSpeed, double aYawHead)
2068 { return SetVelHead(aXSpeed, 0, aYawHead);}
2069
2070
2075
2078 { player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
2079
2082 void GoTo(double aX, double aY, double aYaw)
2083 { player_pose2d_t pos = {aX,aY,aYaw}; player_pose2d_t vel = {0,0,0}; GoTo(pos, vel); }
2084
2086 void SetCarlike(double aXSpeed, double aDriveAngle);
2087
2091
2093 // body (fill it in by calling RequestGeom()).
2095 {
2097 scoped_lock_t lock(mPc->mMutex);
2098 p.px = mDevice->pose[0];
2099 p.py = mDevice->pose[1];
2100 p.pyaw = mDevice->pose[2];
2101 return(p);
2102 }
2103
2106 {
2108 scoped_lock_t lock(mPc->mMutex);
2109 b.sl = mDevice->size[0];
2110 b.sw = mDevice->size[1];
2111 return(b);
2112 }
2113
2118 void SetMotorEnable(bool enable);
2119
2120 // Select velocity control mode.
2121 //
2122 // For the the p2os_position driver, set @p mode to 0 for direct wheel
2123 // velocity control (default), or 1 for separate translational and
2124 // rotational control.
2125 //
2126 // For the reb_position driver: 0 is direct velocity control, 1 is for
2127 // velocity-based heading PD controller (uses DoDesiredHeading()).
2128 //void SelectVelocityControl(unsigned char mode);
2129
2132
2133 // Select position mode
2134 // Set @p mode for 0 for velocity mode, 1 for position mode.
2135 //void SelectPositionMode(unsigned char mode);
2136
2139 void SetOdometry(double aX, double aY, double aYaw);
2140
2141 // Set PID terms
2142 //void SetSpeedPID(double kp, double ki, double kd);
2143
2144 // Set PID terms
2145 //void SetPositionPID(double kp, double ki, double kd);
2146
2147 // Set speed ramping profile
2148 // spd rad/s, acc rad/s/s
2149 //void SetPositionSpeedProfile(double spd, double acc);
2150
2151 //
2152 // void DoStraightLine(double m);
2153
2154 //
2155 //void DoRotation(double yawspeed);
2156
2157 //
2158 //void DoDesiredHeading(double yaw, double xspeed, double yawspeed);
2159
2160 //
2161 //void SetStatus(uint8_t cmd, uint16_t value);
2162
2163 //
2164 //void PlatformShutdown();
2165
2167 double GetXPos() const { return GetVar(mDevice->px); };
2168
2170 double GetYPos() const { return GetVar(mDevice->py); };
2171
2173 double GetYaw() const { return GetVar(mDevice->pa); };
2174
2176 double GetXSpeed() const { return GetVar(mDevice->vx); };
2177
2179 double GetYSpeed() const { return GetVar(mDevice->vy); };
2180
2182 double GetYawSpeed() const { return GetVar(mDevice->va); };
2183
2185 bool GetStall() const { return GetVar(mDevice->stall) != 0 ? true : false; };
2186
2187};
2188
2195class PLAYERCC_EXPORT Position3dProxy : public ClientProxy
2196{
2197
2198 private:
2199
2200 void Subscribe(uint32_t aIndex);
2201 void Unsubscribe();
2202
2203 // libplayerc data structure
2204 playerc_position3d_t *mDevice;
2205
2206 public:
2207
2209 Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
2212
2216 void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed,
2217 double aRollSpeed, double aPitchSpeed, double aYawSpeed);
2218
2222 void SetSpeed(double aXSpeed, double aYSpeed,
2223 double aZSpeed, double aYawSpeed)
2224 { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
2225
2227 void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
2228 { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
2229
2232 void SetSpeed(double aXSpeed, double aYawSpeed)
2233 { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
2234
2237 { SetSpeed(vel.px,vel.py,vel.pz,vel.proll,vel.ppitch,vel.pyaw);}
2238
2243
2246 { player_pose3d_t vel = {0,0,0,0,0,0}; GoTo(aPos, vel); }
2247
2248
2251 void GoTo(double aX, double aY, double aZ,
2252 double aRoll, double aPitch, double aYaw)
2253 { player_pose3d_t pos = {aX,aY,aZ,aRoll,aPitch,aYaw};
2254 player_pose3d_t vel = {0,0,0,0,0,0};
2255 GoTo(pos, vel);
2256 }
2257
2262 void SetMotorEnable(bool aEnable);
2263
2266 void SelectVelocityControl(int aMode);
2267
2270
2274 void SetOdometry(double aX, double aY, double aZ,
2275 double aRoll, double aPitch, double aYaw);
2276
2280
2281 // Select position mode
2282 // Set @p mode for 0 for velocity mode, 1 for position mode.
2283 //void SelectPositionMode(unsigned char mode);
2284
2285 //
2286 //void SetSpeedPID(double kp, double ki, double kd);
2287
2288 //
2289 //void SetPositionPID(double kp, double ki, double kd);
2290
2291 // Sets the ramp profile for position based control
2292 // spd rad/s, acc rad/s/s
2293 //void SetPositionSpeedProfile(double spd, double acc);
2294
2296 double GetXPos() const { return GetVar(mDevice->pos_x); };
2297
2299 double GetYPos() const { return GetVar(mDevice->pos_y); };
2300
2302 double GetZPos() const { return GetVar(mDevice->pos_z); };
2303
2305 double GetRoll() const { return GetVar(mDevice->pos_roll); };
2306
2308 double GetPitch() const { return GetVar(mDevice->pos_pitch); };
2309
2311 double GetYaw() const { return GetVar(mDevice->pos_yaw); };
2312
2314 double GetXSpeed() const { return GetVar(mDevice->vel_x); };
2315
2317 double GetYSpeed() const { return GetVar(mDevice->vel_y); };
2318
2320 double GetZSpeed() const { return GetVar(mDevice->vel_z); };
2321
2323 double GetRollSpeed() const { return GetVar(mDevice->vel_roll); };
2324
2326 double GetPitchSpeed() const { return GetVar(mDevice->vel_pitch); };
2327
2329 double GetYawSpeed() const { return GetVar(mDevice->vel_yaw); };
2330
2332 bool GetStall () const { return GetVar(mDevice->stall) != 0 ? true : false; };
2333};
2336class PLAYERCC_EXPORT PowerProxy : public ClientProxy
2337{
2338 private:
2339
2340 void Subscribe(uint32_t aIndex);
2341 void Unsubscribe();
2342
2343 // libplayerc data structure
2344 playerc_power_t *mDevice;
2345
2346 public:
2348 PowerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2351
2353 double GetCharge() const { return GetVar(mDevice->charge); };
2354
2356 double GetPercent() const {return GetVar(mDevice->percent); };
2357
2359 double GetJoules() const {return GetVar(mDevice->joules); };
2360
2362 double GetWatts() const {return GetVar(mDevice->watts); };
2363
2365 bool GetCharging() const {return GetVar(mDevice->charging) != 0 ? true : false;};
2366
2367 // Return whether the power data is valid
2368 bool IsValid() const {return GetVar(mDevice->valid) != 0 ? true : false;};
2369};
2370
2377class PLAYERCC_EXPORT PtzProxy : public ClientProxy
2378{
2379
2380 private:
2381
2382 void Subscribe(uint32_t aIndex);
2383 void Unsubscribe();
2384
2385 // libplayerc data structure
2386 playerc_ptz_t *mDevice;
2387
2388 public:
2389 // Constructor
2390 PtzProxy(PlayerClient *aPc, uint32_t aIndex=0);
2391 // Destructor
2392 ~PtzProxy();
2393
2394 public:
2395
2399 void SetCam(double aPan, double aTilt, double aZoom);
2400
2402 void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0);
2403
2406 void SelectControlMode(uint32_t aMode);
2407
2409 double GetPan() const { return GetVar(mDevice->pan); };
2411 double GetTilt() const { return GetVar(mDevice->tilt); };
2413 double GetZoom() const { return GetVar(mDevice->zoom); };
2414
2417
2418
2419};
2420
2423class PLAYERCC_EXPORT RangerProxy : public ClientProxy
2424{
2425 private:
2426
2427 void Subscribe(uint32_t aIndex);
2428 void Unsubscribe();
2429
2430 // libplayerc data structure
2431 playerc_ranger_t *mDevice;
2432
2433 public:
2435 RangerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2438
2440 uint32_t GetElementCount() const { return GetVar(mDevice->element_count); };
2441
2443 player_pose3d_t GetDevicePose() const { return GetVar(mDevice->device_pose); };
2445 player_bbox3d_t GetDeviceSize() const { return GetVar(mDevice->device_size); };
2446
2448 player_pose3d_t GetElementPose(uint32_t aIndex) const;
2450 player_bbox3d_t GetElementSize(uint32_t aIndex) const;
2451
2453 uint32_t GetRangeCount() const { return GetVar(mDevice->ranges_count); };
2455 double GetRange(uint32_t aIndex) const;
2457 double operator[] (uint32_t aIndex) const { return GetRange(aIndex); }
2458
2460 uint32_t GetPointCount() const { return GetVar(mDevice->points_count); };
2462 player_point_3d_t GetPoint(uint32_t aIndex) const;
2463
2465 uint32_t GetIntensityCount() const { return GetVar(mDevice->intensities_count); } ;
2467 double GetIntensity(uint32_t aIndex) const;
2468
2471 void SetPower(bool aEnable);
2472
2475 void SetIntensityData(bool aEnable);
2476
2479
2484 void Configure(double aMinAngle,
2485 double aMaxAngle,
2486 double aAngularRes,
2487 double aMinRange,
2488 double aMaxRange,
2489 double aRangeRes,
2490 double aFrequency);
2491
2495
2497 double GetMinAngle() const { return GetVar(mDevice->min_angle); };
2498
2500 double GetMaxAngle() const { return GetVar(mDevice->max_angle); };
2501
2503 double GetAngularRes() const { return GetVar(mDevice->angular_res); };
2504
2506 double GetMinRange() const { return GetVar(mDevice->min_range); };
2507
2509 double GetMaxRange() const { return GetVar(mDevice->max_range); };
2510
2512 double GetRangeRes() const { return GetVar(mDevice->range_res); };
2513
2515 double GetFrequency() const { return GetVar(mDevice->frequency); };
2516};
2517
2520class PLAYERCC_EXPORT RFIDProxy : public ClientProxy
2521{
2522
2523 private:
2524
2525 void Subscribe(uint32_t aIndex);
2526 void Unsubscribe();
2527
2528 // libplayerc data structure
2529 playerc_rfid_t *mDevice;
2530
2531 public:
2533 RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0);
2536
2538 uint32_t GetTagsCount() const { return GetVar(mDevice->tags_count); };
2540 playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
2541 { return GetVar(mDevice->tags[aIndex]);};
2542
2547 playerc_rfidtag_t operator [](uint32_t aIndex) const
2548 { return(GetRFIDTag(aIndex)); }
2549};
2550
2555class PLAYERCC_EXPORT SimulationProxy : public ClientProxy
2556{
2557 private:
2558
2559 void Subscribe(uint32_t aIndex);
2560 void Unsubscribe();
2561
2562 // libplayerc data structure
2563 playerc_simulation_t *mDevice;
2564
2565 public:
2567 SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0);
2570
2573 void SetPose2d(char* identifier, double x, double y, double a);
2574
2577 void GetPose2d(char* identifier, double& x, double& y, double& a);
2578
2581 void SetPose3d(char* identifier, double x, double y, double z,
2582 double roll, double pitch, double yaw);
2583
2586 void GetPose3d(char* identifier, double& x, double& y, double& z,
2587 double& roll, double& pitch, double& yaw, double& time);
2588
2590 void GetProperty(char* identifier, char *name, void *value, size_t value_len );
2591
2593 void SetProperty(char* identifier, char *name, void *value, size_t value_len );
2594};
2595
2596
2602class PLAYERCC_EXPORT SonarProxy : public ClientProxy
2603{
2604 private:
2605
2606 void Subscribe(uint32_t aIndex);
2607 void Unsubscribe();
2608
2609 // libplayerc data structure
2610 playerc_sonar_t *mDevice;
2611
2612 public:
2614 SonarProxy(PlayerClient *aPc, uint32_t aIndex=0);
2617
2619 uint32_t GetCount() const { return GetVar(mDevice->scan_count); };
2620
2622 double GetScan(uint32_t aIndex) const
2623 { if (GetVar(mDevice->scan_count) <= (int32_t)aIndex) return -1.0; return GetVar(mDevice->scan[aIndex]); };
2626 double operator [] (uint32_t aIndex) const { return GetScan(aIndex); }
2627
2629 uint32_t GetPoseCount() const { return GetVar(mDevice->pose_count); };
2630
2632 player_pose3d_t GetPose(uint32_t aIndex) const
2633 { return GetVar(mDevice->poses[aIndex]); };
2634
2635 // Enable/disable the sonars.
2636 // Set @p state to 1 to enable, 0 to disable.
2637 // Note that when sonars are disabled the client will still receive sonar
2638 // data, but the ranges will always be the last value read from the sonars
2639 // before they were disabled.
2640 //void SetEnable(bool aEnable);
2641
2644};
2645
2650class PLAYERCC_EXPORT SpeechProxy : public ClientProxy
2651{
2652
2653 private:
2654
2655 void Subscribe(uint32_t aIndex);
2656 void Unsubscribe();
2657
2658 // libplayerc data structure
2659 playerc_speech_t *mDevice;
2660
2661 public:
2663 SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0);
2666
2669 void Say(std::string aStr);
2670};
2671
2675class PLAYERCC_EXPORT SpeechRecognitionProxy : public ClientProxy
2676{
2677 void Subscribe(uint32_t aIndex);
2678 void Unsubscribe();
2679
2682 public:
2684 SpeechRecognitionProxy(PlayerClient *aPc, uint32_t aIndex=0);
2688 std::string GetWord(uint32_t aWord) const{
2689 scoped_lock_t lock(mPc->mMutex);
2690 return std::string(mDevice->words[aWord]);
2691 }
2692
2694 uint32_t GetCount(void) const { return GetVar(mDevice->wordCount); }
2695
2698 std::string operator [](uint32_t aWord) { return(GetWord(aWord)); }
2699};
2700
2704class PLAYERCC_EXPORT StereoProxy : public ClientProxy
2705{
2706 private:
2707 void Subscribe(uint32_t aIndex);
2708 void Unsubscribe();
2709
2712
2714 void SaveFrame(const std::string aPrefix, uint32_t aWidth, playerc_camera_t aDevice, uint8_t aIndex);
2715
2718
2720 std::string mPrefix;
2721
2723 uint32_t mFrameNo[3];
2724
2725 public:
2727 StereoProxy(PlayerClient *aPc, uint32_t aIndex=0);
2728
2731
2735 void SaveLeftFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->left_channel, 0); };
2739 void SaveRightFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->right_channel, 1); };
2743 void SaveDisparityFrame(const std::string aPrefix, uint32_t aWidth=4) {return SaveFrame(aPrefix, aWidth, mDevice->disparity, 2); };
2744
2746 void DecompressLeft(){ return Decompress(mDevice->left_channel); };
2748 void DecompressRight(){ return Decompress(mDevice->right_channel); };
2750 void DecompressDisparity(){ return Decompress(mDevice->disparity); };
2751
2753 uint32_t GetLeftDepth() const { return GetVar(mDevice->left_channel.bpp); };
2755 uint32_t GetRightDepth() const { return GetVar(mDevice->right_channel.bpp); };
2757 uint32_t GetDisparityDepth() const { return GetVar(mDevice->disparity.bpp); };
2758
2760 uint32_t GetLeftWidth() const { return GetVar(mDevice->left_channel.width); };
2762 uint32_t GetRightWidth() const { return GetVar(mDevice->right_channel.width); };
2764 uint32_t GetDisparityWidth() const { return GetVar(mDevice->disparity.width); };
2765
2767 uint32_t GetLeftHeight() const { return GetVar(mDevice->left_channel.height); };
2769 uint32_t GetRightHeight() const { return GetVar(mDevice->right_channel.height); };
2771 uint32_t GetDisparityHeight() const { return GetVar(mDevice->disparity.height); };
2772
2779 uint32_t GetLeftFormat() const { return GetVar(mDevice->left_channel.format); };
2786 uint32_t GetRightFormat() const { return GetVar(mDevice->right_channel.format); };
2793 uint32_t GetDisparityFormat() const { return GetVar(mDevice->disparity.format); };
2794
2796 uint32_t GetLeftImageSize() const { return GetVar(mDevice->left_channel.image_count); };
2798 uint32_t GetRightImageSize() const { return GetVar(mDevice->right_channel.image_count); };
2800 uint32_t GetDisparityImageSize() const { return GetVar(mDevice->disparity.image_count); };
2801
2806 void GetLeftImage(uint8_t* aImage) const
2807 {
2808 return GetVarByRef(mDevice->left_channel.image,
2809 mDevice->left_channel.image+GetVar(mDevice->left_channel.image_count),
2810 aImage);
2811 };
2816 void GetRightImage(uint8_t* aImage) const
2817 {
2818 return GetVarByRef(mDevice->right_channel.image,
2819 mDevice->right_channel.image+GetVar(mDevice->right_channel.image_count),
2820 aImage);
2821 };
2826 void GetDisparityImage(uint8_t* aImage) const
2827 {
2828 return GetVarByRef(mDevice->disparity.image,
2829 mDevice->disparity.image+GetVar(mDevice->disparity.image_count),
2830 aImage);
2831 };
2832
2837 uint32_t GetLeftCompression() const { return GetVar(mDevice->left_channel.compression); };
2842 uint32_t GetRightCompression() const { return GetVar(mDevice->right_channel.compression); };
2847 uint32_t GetDisparityCompression() const { return GetVar(mDevice->disparity.compression); };
2848
2850 uint32_t GetCount() const { return GetVar(mDevice->points_count); };
2851
2853 player_pointcloud3d_stereo_element_t GetPoint(uint32_t aIndex) const
2854 { return GetVar(mDevice->points[aIndex]); };
2855
2858 player_pointcloud3d_stereo_element_t operator [] (uint32_t aIndex) const { return GetPoint(aIndex); }
2859
2860};
2861
2865class PLAYERCC_EXPORT VectorMapProxy : public ClientProxy
2866{
2867
2868 private:
2869
2870 // Subscribe
2871 void Subscribe(uint32_t aIndex);
2872 // Unsubscribe
2873 void Unsubscribe();
2874
2875 // libplayerc data structure
2876 playerc_vectormap_t *mDevice;
2877
2878 bool map_info_cached;
2879 public:
2881 VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0);
2884
2887
2889 void GetLayerData(unsigned layer_index);
2890
2892 int GetLayerCount() const;
2893
2895 std::vector<std::string> GetLayerNames() const;
2896
2898 int GetFeatureCount(unsigned layer_index) const;
2899
2901 const uint8_t * GetFeatureData(unsigned layer_index, unsigned feature_index) const;
2902
2904 size_t GetFeatureDataCount(unsigned layer_index, unsigned feature_index) const;
2905};
2906
2909class PLAYERCC_EXPORT WiFiProxy: public ClientProxy
2910{
2911
2912 private:
2913
2914 void Subscribe(uint32_t aIndex);
2915 void Unsubscribe();
2916
2917 // libplayerc data structure
2918 playerc_wifi_t *mDevice;
2919
2920 public:
2922 WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0);
2925
2927 const playerc_wifi_link_t *GetLink(int aLink);
2928
2930 int GetLinkCount() const { return mDevice->link_count; };
2932 char* GetOwnIP() const { return mDevice->ip; };
2934 char* GetLinkIP(int index) const { return (char*) mDevice->links[index].ip; };
2936 char* GetLinkMAC(int index) const { return (char*) mDevice->links[index].mac; };
2938 char* GetLinkESSID(int index) const { return (char*)mDevice->links[index].essid; };
2940 double GetLinkFreq(int index) const {return mDevice->links[index].freq;};
2942 int GetLinkMode(int index) const { return mDevice->links[index].mode; };
2944 int GetLinkEncrypt(int index) const {return mDevice->links[index].encrypt; };
2946 int GetLinkQuality(int index) const { return mDevice->links[index].qual; };
2948 int GetLinkLevel(int index) const {return mDevice->links[index].level; };
2950 int GetLinkNoise(int index) const {return mDevice->links[index].noise; } ;
2951
2952};
2953
2956class PLAYERCC_EXPORT WSNProxy : public ClientProxy
2957{
2958
2959 private:
2960
2961 void Subscribe(uint32_t aIndex);
2962 void Unsubscribe();
2963
2964 // libplayerc data structure
2965 playerc_wsn_t *mDevice;
2966
2967 public:
2969 WSNProxy(PlayerClient *aPc, uint32_t aIndex=0);
2972
2974 uint32_t GetNodeType () const { return GetVar(mDevice->node_type); };
2976 uint32_t GetNodeID () const { return GetVar(mDevice->node_id); };
2978 uint32_t GetNodeParentID() const { return GetVar(mDevice->node_parent_id); };
2979
2981 player_wsn_node_data_t
2982 GetNodeDataPacket() const { return GetVar(mDevice->data_packet); };
2983
2985 void SetDevState(int nodeID, int groupID, int devNr, int value);
2987 void Power(int nodeID, int groupID, int value);
2989 void DataType(int value);
2991 void DataFreq(int nodeID, int groupID, float frequency);
2992};
2993
2995}
2996
2997namespace std
2998{
2999 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_point_2d_t& c);
3000 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose2d_t& c);
3001 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_pose3d_t& c);
3002 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox2d_t& c);
3003 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_bbox3d_t& c);
3004 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_segment_t& c);
3005 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const player_extent2d_t& c);
3006 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const playerc_device_info_t& c);
3007
3008 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ClientProxy& c);
3009 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ActArrayProxy& c);
3010 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AioProxy& c);
3011 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::AudioProxy& a);
3012 //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlinkenLightProxy& c);
3013 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BlobfinderProxy& c);
3014 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::BumperProxy& c);
3015 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::CameraProxy& c);PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::CoopObjectProxy& c);
3016 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::DioProxy& c);
3017 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::FiducialProxy& c);
3018 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GpsProxy& c);
3019 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::GripperProxy& c);
3020 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::ImuProxy& c);
3021 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::IrProxy& c);
3022 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LaserProxy& c);
3023 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LimbProxy& c);
3024 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LinuxjoystickProxy& c);
3025 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LocalizeProxy& c);
3026 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::LogProxy& c);
3027 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::MapProxy& c);
3028 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::OpaqueProxy& c);
3029 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PlannerProxy& c);
3030 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position1dProxy& c);
3031 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position2dProxy& c);
3032 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::Position3dProxy& c);
3033 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PowerProxy& c);
3034 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::PtzProxy& c);
3035 PLAYERCC_EXPORT std::ostream& operator << (std::ostream &os, const PlayerCc::RangerProxy &c);
3036 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SimulationProxy& c);
3037 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SonarProxy& c);
3038 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechProxy& c);
3039 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::SpeechRecognitionProxy& c);
3040 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::StereoProxy& c);
3041 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::VectorMapProxy& c);
3042 //PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WafeformProxy& c);
3043 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WiFiProxy& c);
3044 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::RFIDProxy& c);
3045 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os, const PlayerCc::WSNProxy& c);
3046}
3047
3048#endif
3049
The ActArrayProxy class is used to control a interface_actarray device.
Definition playerc++.h:142
void SetActuatorCurrentMulti(std::vector< float > aCurrent)
Set actuators 0 thru n to the given currents.
void MoveToMulti(std::vector< float > aPos)
Send actuators 0 thru n to the designated positions.
void MoveAtSpeed(uint32_t aJoint, float aSpeed)
Move an actuator at a speed.
player_point_3d_t GetBasePos(void) const
Accessor method for getting the base position.
Definition playerc++.h:193
void SetAccelerationConfig(uint32_t aJoint, float aAcc)
Acceleration control.
void SetSpeedConfig(uint32_t aJoint, float aSpeed)
Speed control.
player_orientation_3d_t GetBaseOrientation(void) const
Accessor method for getting the base orientation.
Definition playerc++.h:195
void MoveAtSpeedMulti(std::vector< float > aSpeed)
Move actuators 0 thru n at the designated speeds.
void MoveTo(uint32_t aJoint, float aPos)
Send an actuator to a position.
~ActArrayProxy()
Default destructor.
void SetBrakesConfig(bool aVal)
Brakes control.
uint32_t GetCount(void) const
Gets the number of actuators in the array.
Definition playerc++.h:187
void MoveHome(int aJoint)
Send an actuator, or all actuators, home.
void SetActuatorCurrent(uint32_t aJoint, float aCurrent)
Set an actuator to a given current.
void RequestGeometry(void)
Geometry request - call before getting the geometry of a joint through the accessor method.
void SetPowerConfig(bool aVal)
Power control.
player_actarray_actuator_t GetActuatorData(uint32_t aJoint) const
Accessor method for getting an actuator's data.
ActArrayProxy(PlayerClient *aPc, uint32_t aIndex=0)
Default constructor.
player_actarray_actuatorgeom_t GetActuatorGeom(uint32_t aJoint) const
Same again for getting actuator geometry.
The AioProxy class is used to read from a interface_aio (analog I/O) device.
Definition playerc++.h:210
uint32_t GetCount() const
Get number of voltages.
Definition playerc++.h:227
AioProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void SetVoltage(uint32_t aIndex, double aVoltage)
Set an output voltage.
double GetVoltage(uint32_t aIndex) const
Get an input voltage.
Definition playerc++.h:230
~AioProxy()
Destructor.
The AudioProxy class controls an interface_audio device.
Definition playerc++.h:250
void GetMixerLevels()
Request mixer channel data result is stored in mixer_data.
uint32_t GetWavDataLength() const
Get Wav data length.
Definition playerc++.h:277
uint32_t GetState(void) const
Get driver state.
Definition playerc++.h:299
void RecordWav()
Request to record a single audio block result is stored in wav_data.
player_audio_mixer_channel_t GetChannel(int aIndex) const
Get Sequence item.
Definition playerc++.h:297
void SetWavStremRec(bool aState)
Command to set recording state.
void GetSample(int aIndex)
Request to retrieve an audio sample Data is stored in wav_data.
AudioProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void PlaySeq(player_audio_seq_t *aTones)
Command to play sequence of tones.
player_audio_seq_item_t GetSeqItem(int aIndex) const
Get Sequence item.
Definition playerc++.h:292
uint32_t GetMixerDetailsCount() const
Get Mixer Details Count.
Definition playerc++.h:268
void SetMultMixerLevels(player_audio_mixer_channel_list_t *aLevels)
Command to set multiple mixer levels.
uint32_t GetDefaultOutputChannel() const
Get Default output Channel.
Definition playerc++.h:272
void SetMixerLevel(uint32_t index, float amplitude, uint8_t active)
Command to set a single mixer level.
void RecordSample(int aIndex, uint32_t aLength)
Request to record new sample.
~AudioProxy()
Destructor.
void LoadSample(int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat)
Request to load an audio sample.
uint32_t GetChannelCount() const
Get Channel data count.
Definition playerc++.h:295
uint32_t GetDefaultInputChannel() const
Get Default input Channel.
Definition playerc++.h:274
player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const
Get Mixer Detail.
Definition playerc++.h:270
void PlaySample(int aIndex)
Command to play prestored sample.
void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat)
Command to play an audio block.
uint32_t GetSeqCount() const
Get Seq data count.
Definition playerc++.h:290
void GetMixerDetails()
Request mixer channel details list result is stored in channel_details_list.
void GetWavData(uint8_t *aData) const
Get Wav data This function copies the wav data into the buffer aImage.
Definition playerc++.h:282
The BlackBoardProxy class is used to subscribe to a blackboard device.
Definition playerc++.h:353
BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void SetEventHandler(void(*on_blackboard_event)(playerc_blackboard_t *, player_blackboard_entry_t))
Set the function pointer which will be called when an entry is updated.
player_blackboard_entry_t * SubscribeToKey(const char *key, const char *group="")
Subscribe to a key.
void SubscribeToGroup(const char *key)
Subscribe to a group.
void UnsubscribeFromGroup(const char *group)
Stop receiving updates about this group.
~BlackBoardProxy()
Destructor.
void UnsubscribeFromKey(const char *key, const char *group="")
Stop receiving updates about this key.
void SetEntry(const player_blackboard_entry_t &entry)
Set a key value.
player_blackboard_entry_t * GetEntry(const char *key, const char *group)
Get a value for a key.
The BlinkenlightProxy class is used to enable and disable a flashing indicator light,...
Definition playerc++.h:426
uint32_t GetWidth() const
get the width of the image
Definition playerc++.h:448
~BlobfinderProxy()
Destructor.
playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
returns a blob
Definition playerc++.h:444
uint32_t GetHeight() const
get the height of the image
Definition playerc++.h:450
uint32_t GetCount() const
returns the number of blobs
Definition playerc++.h:442
BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The BumperProxy class is used to read from a interface_bumper device.
Definition playerc++.h:477
bool IsAnyBumped()
Returns true if any bumper has been bumped, false otherwise.
player_bumper_define_t GetPose(uint32_t aIndex) const
Returns a specific bumper pose.
Definition playerc++.h:511
void RequestBumperConfig()
Requests the geometries of the bumpers.
uint32_t GetCount() const
Returns how many bumpers are in underlying device.
Definition playerc++.h:495
~BumperProxy()
Destructor.
uint32_t GetPoseCount() const
Returns the number bumper poses.
Definition playerc++.h:508
uint32_t IsBumped(uint32_t aIndex) const
Returns true if the specified bumper has been bumped, false otherwise.
Definition playerc++.h:498
BumperProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The CameraProxy class can be used to get images from a interface_camera device.
Definition playerc++.h:527
CameraProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void Decompress()
decompress the image
uint32_t GetDepth() const
Image color depth.
Definition playerc++.h:557
uint32_t GetCompression() const
What is the compression type? Currently supported compression types are:
Definition playerc++.h:591
uint32_t GetImageSize() const
Size of the image (bytes)
Definition playerc++.h:574
void SaveFrame(const std::string aPrefix, uint32_t aWidth=4)
Save the frame.
uint32_t GetHeight() const
Image dimensions (pixels)
Definition playerc++.h:563
uint32_t GetWidth() const
Image dimensions (pixels)
Definition playerc++.h:560
void GetImage(uint8_t *aImage) const
Image data This function copies the image data into the data buffer aImage.
Definition playerc++.h:580
virtual ~CameraProxy()
Destructor.
uint32_t GetFormat() const
Image format Possible values include.
Definition playerc++.h:571
The client proxy base class.
Definition clientproxy.h:80
The CoopObjectProxy class is used to control a interface_coopobject device.
Definition playerc++.h:599
uint8_t GetParameter(uint32_t index) const
Indexed user defined byte.
Definition playerc++.h:742
void SetProxyID(uint32_t value)
Set robot ID.
Definition playerc++.h:648
uint32_t GetAlarmNumber() const
Get number of alarms included in the message.
Definition playerc++.h:678
void SendCommand(int destID, int sourceID, int command, uint32_t cmd_parameters_size=0, uint8_t *cmd_parameters=NULL)
Send command to Cooperating Object.
float GetZ() const
Cooperating Object Z position.
Definition playerc++.h:729
uint8_t GetSensorType(uint32_t index) const
Sensor type Possible values include.
Definition playerc++.h:672
int MessageType() const
Message type Possible values include.
Definition playerc++.h:628
uint32_t GetCommand() const
Command type.
Definition playerc++.h:736
uint16_t GetRSSIstamp() const
Radio Signal Strength message timestamp.
Definition playerc++.h:720
~CoopObjectProxy()
Destructor.
uint16_t GetRSSIvalue() const
Radio Signal Strength value.
Definition playerc++.h:718
uint32_t GetProxyID() const
Get robot ID.
Definition playerc++.h:645
uint32_t GetUserDataNumber() const
Get number of bytes of user defined data.
Definition playerc++.h:707
uint16_t GetRSSIsenderId() const
Radio Signal Strength sender ID.
Definition playerc++.h:716
uint32_t GetParentID() const
Cooperating Object Parent ID.
Definition playerc++.h:642
double GetRSSInodeTime() const
Radio Signal Strength Cooperating Object timestamp.
Definition playerc++.h:722
uint8_t * GetAllParameters() const
Request/Command parameter array.
Definition playerc++.h:740
float GetX() const
Cooperating Object X position.
Definition playerc++.h:725
CoopObjectProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
float GetY() const
Cooperating Object Y position.
Definition playerc++.h:727
uint8_t GetAlarmType(uint32_t index) const
Alarm type Possible values include.
Definition playerc++.h:701
void SendRequest(int destID, int sourceID, int request, uint32_t req_parameters_size=0, uint8_t *req_parameters=NULL)
Send request to Cooperating Object.
uint16_t GetAlarmData(uint32_t index) const
Alarm value.
Definition playerc++.h:704
void SendData(int destID, int sourceID, player_pose2d_t pos, int status)
Send user data to Cooperating Object.
uint8_t GetStatus() const
Cooperating Object status.
Definition playerc++.h:731
uint32_t GetRequest() const
Request type.
Definition playerc++.h:734
uint32_t GetParametersSize() const
Request/Command parameter array size (in bytes)
Definition playerc++.h:738
void SendData(int destID, int sourceID, int extradata_type, uint32_t extradata_size, uint8_t *extradata)
Send user data to Cooperating Object.
uint16_t GetSensorData(uint32_t index) const
Sensor value.
Definition playerc++.h:675
uint32_t GetOrigin() const
Cooperating Object type Possible values include.
Definition playerc++.h:636
uint8_t * GetAllUserData() const
User defined data array.
Definition playerc++.h:710
uint8_t GetUserData(uint32_t index) const
Indexed user defined byte.
Definition playerc++.h:713
uint32_t GetID() const
Cooperating Object ID.
Definition playerc++.h:639
uint32_t GetSensorNumber() const
Get number of sensors included in the message.
Definition playerc++.h:651
The DioProxy class is used to read from a interface_dio (digital I/O) device.
Definition playerc++.h:766
uint32_t GetCount() const
The number of valid digital inputs.
Definition playerc++.h:782
void SetOutput(uint32_t aCount, uint32_t aDigout)
Set the output to the bitfield aDigout.
uint32_t GetDigin() const
A bitfield of the current digital inputs.
Definition playerc++.h:785
~DioProxy()
Destructor.
DioProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
bool GetInput(uint32_t aIndex) const
Get a specific bit.
The FiducialProxy class is used to control interface_fiducial devices.
Definition playerc++.h:807
player_pose3d_t GetSensorPose() const
The pose of the sensor.
Definition playerc++.h:829
player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const
Get detected beacon description.
Definition playerc++.h:825
player_bbox3d_t GetSensorSize() const
The size of the sensor.
Definition playerc++.h:833
uint32_t GetCount() const
The number of beacons detected.
Definition playerc++.h:822
void RequestGeometry()
Get the sensor's geometry configuration.
FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
player_bbox2d_t GetFiducialSize() const
The size of the most recently detected fiducial.
Definition playerc++.h:837
~FiducialProxy()
Destructor.
The GpsProxy class is used to control a interface_gps device.
Definition playerc++.h:855
uint32_t GetQuality() const
Fix quality.
Definition playerc++.h:890
~GpsProxy()
Destructor.
double GetCourse() const
Course made good (heading if the robot moves along its longitudinal axis), in radians.
Definition playerc++.h:884
double GetErrHorizontal() const
Errors.
Definition playerc++.h:906
double GetVdop() const
Vertical dilution of position (HDOP)
Definition playerc++.h:896
uint32_t GetSatellites() const
Number of satellites in view.
Definition playerc++.h:887
double GetHdop() const
Horizontal dilution of position (HDOP)
Definition playerc++.h:893
GpsProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
double GetAltitude() const
Altitude, in meters.
Definition playerc++.h:877
double GetTime() const
Time, since the epoch.
Definition playerc++.h:903
double GetLatitude() const
Latitude and longitude, in degrees.
Definition playerc++.h:873
double GetUtmEasting() const
UTM easting and northing (meters).
Definition playerc++.h:899
double GetSpeed() const
Spped over ground, in m/s.
Definition playerc++.h:880
The Graphics2dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition playerc++.h:918
void DrawMultiline(player_point_2d_t pts[], int count)
Draw multiple lines. Lines ending points are at pts[2n] pts[2n+1] where 2n+1<count.
void DrawPolygon(player_point_2d_t pts[], int count, bool filled, player_color_t fill_color)
Draw a polygon defined by a set of points.
Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void DrawPolyline(player_point_2d_t pts[], int count)
Draw a line connecting set of points.
void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha)
Set the current pen color.
~Graphics2dProxy()
Destructor.
void DrawPoints(player_point_2d_t pts[], int count)
Draw a set of points.
void Clear(void)
Clear the drawing area.
void Color(player_color_t col)
Set the current pen color.
The Graphics3dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition playerc++.h:968
void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha)
Set the current pen color.
~Graphics3dProxy()
Destructor.
void Draw(player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count)
Draw a set of verticies.
void Color(player_color_t col)
Set the current pen color.
void Clear(void)
Clear the drawing area.
Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The GripperProxy class is used to control a interface_gripper device.
Definition playerc++.h:1005
void RequestGeometry(void)
Geometry request - call before getting the geometry of the gripper through an accessor method.
player_bbox3d_t GetInnerSize() const
Get the inner size of the gripper.
Definition playerc++.h:1035
void Open()
Command the gripper to open.
uint32_t GetCapacity() const
Get the capacity of the gripper's storage.
Definition playerc++.h:1039
void Close()
Command the gripper to close.
void Retrieve()
Command the gripper to retrieve.
uint32_t GetNumBeams() const
Get the number of breakbeams in the gripper.
Definition playerc++.h:1037
GripperProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
~GripperProxy()
Destructor.
player_pose3d_t GetPose() const
Get the pose of the gripper.
Definition playerc++.h:1031
void Store()
Command the gripper to store.
void Stop()
Command the gripper to stop.
uint32_t GetBeams() const
Get the gripper break beam info.
Definition playerc++.h:1029
uint32_t GetState() const
Get the gripper state.
Definition playerc++.h:1027
uint32_t GetStored() const
Get the number of currently-stored objects.
Definition playerc++.h:1041
player_bbox3d_t GetOuterSize() const
Get the outer size of the gripper.
Definition playerc++.h:1033
The HealthProxy class is used to get infos of the player-server.
Definition playerc++.h:1058
float GetPercSwapUsed()
Get percentage of used SWAP.
int64_t GetSwapUsed()
Get amount of swap used.
~HealthProxy()
Destructor.
int64_t GetMemFree()
Get amount of free memory.
int64_t GetMemUsed()
Get amount of memory used.
int64_t GetSwapTotal()
Get total amount of swap.
int64_t GetSwapFree()
Get amount of free swap space.
float GetSystemCPU()
Get system CPU load in percents.
HealthProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
float GetPercMemUsed()
Get percentage of used RAM.
float GetIdleCPU()
Get idle CPU load in percents.
float GetUserCPU()
Get user CPU load in percents.
int64_t GetMemTotal()
Get total amount of memory.
float GetPercTotalUsed()
Get percentage of totally used memory (swap and ram)
The ImuProxy class is used to control an interface_imu device.
Definition playerc++.h:1118
void ResetEuler(float aRoll, float aPitch, float aYaw)
Reset euler orientation.
void ResetOrientation(int aValue)
Reset orientation.
float GetZMagn()
Get Z Magnetism.
float GetXGyro()
Get X Gyro Rate.
float GetXMagn()
Get X Magnetism.
~ImuProxy()
Destructor.
float GetZAccel()
Get Z Acceleration.
player_pose3d_t GetPose() const
Get the processed pose of the imu.
Definition playerc++.h:1134
player_imu_data_calib_t GetRawValues() const
Get all calibrated values.
Definition playerc++.h:1156
float GetZGyro()
Get Z Gyro Rate.
float GetYMagn()
Get Y Magnetism.
float GetXAccel()
Get X Acceleration.
float GetYGyro()
Get Y Gyro Rate.
float GetYAccel()
Get Y Acceleration.
void SetDatatype(int aDatatype)
Change the data type to one of the predefined data structures.
ImuProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The IrProxy class is used to control an interface_ir device.
Definition playerc++.h:1176
IrProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
double GetVoltage(uint32_t aIndex) const
get the current voltage
Definition playerc++.h:1199
double GetRange(uint32_t aIndex) const
get the current range
Definition playerc++.h:1196
player_pose3d_t GetPose(uint32_t aIndex) const
get a particular pose
Definition playerc++.h:1204
uint32_t GetPoseCount() const
get the number of poses
Definition playerc++.h:1202
~IrProxy()
Destructor.
void RequestGeom()
Request IR pose information.
uint32_t GetCount() const
get the number of IR rangers
Definition playerc++.h:1194
The LaserProxy class is used to control a interface_laser device.
Definition playerc++.h:1225
double GetMinLeft() const
Minimum range reading on the left side.
Definition playerc++.h:1368
double GetRange(uint32_t aIndex) const
get the range
Definition playerc++.h:1287
double GetConfMaxAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition playerc++.h:1272
~LaserProxy()
Destructor.
double GetBearing(uint32_t aIndex) const
get the bearing
Definition playerc++.h:1291
player_pose3d_t GetPose()
Accessor for the pose of the laser with respect to its parent object (e.g., a robot).
Definition playerc++.h:1332
uint32_t GetCount() const
Number of points in scan.
Definition playerc++.h:1246
double GetScanningFrequency() const
Scanning Frequency (Hz)
Definition playerc++.h:1258
double GetMinRight() const
Minimum range reading on the right side.
Definition playerc++.h:1372
int GetIntensity(uint32_t aIndex) const
get the intensity
Definition playerc++.h:1296
void RequestConfigure()
Request the current laser configuration; it is read into the relevant class attributes.
player_pose3d_t GetRobotPose()
Accessor for the pose of the laser's parent object (e.g., a robot).
Definition playerc++.h:1345
double MinRight() const
Definition playerc++.h:1380
bool IntensityOn() const
Whether or not reflectance (i.e., intensity) values are being returned.
Definition playerc++.h:1275
void RequestGeom()
Get the laser's geometry; it is read into the relevant class attributes.
player_point_2d_t GetPoint(uint32_t aIndex) const
Scan data (Cartesian): x,y (m)
Definition playerc++.h:1282
int GetID() const
get the laser ID, call RequestId first
Definition playerc++.h:1300
double GetConfMinAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition playerc++.h:1270
void RequestID()
Request the ID of the laser; read it with GetID()
LaserProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
double MinLeft() const
Definition playerc++.h:1376
double GetMinAngle() const
Scan range for the latest set of data (radians)
Definition playerc++.h:1261
void Configure(double aMinAngle, double aMaxAngle, uint32_t aScanRes, uint32_t aRangeRes, bool aIntensity, double aScanningFrequency)
Configure the laser scan pattern.
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition playerc++.h:1357
double GetMaxAngle() const
Scan range for the latest set of data (radians)
Definition playerc++.h:1263
double GetScanRes() const
Angular resolution of scan (radians)
Definition playerc++.h:1252
double GetRangeRes() const
Range resolution of scan (mm)
Definition playerc++.h:1255
double GetMaxRange() const
Max range for the latest set of data (meters)
Definition playerc++.h:1249
The LimbProxy class is used to control a interface_limb device.
Definition playerc++.h:1398
player_limb_geom_req_t GetGeom(void) const
Same again for getting the limb's geometry.
player_limb_data_t GetData(void) const
Accessor method for getting the limb's data.
~LimbProxy()
Destructor.
void SetPose(float aPX, float aPY, float aPZ, float aAX, float aAY, float aAZ, float aOX, float aOY, float aOZ)
Move the end effector to a given pose.
void SetSpeedConfig(float aSpeed)
Speed control.
void Stop(void)
Stop the limb immediately.
void MoveHome(void)
Move the limb to the home position.
void RequestGeometry(void)
Geometry request - call before getting the geometry of a joint through the accessor method.
void VectorMove(float aX, float aY, float aZ, float aLength)
Move the end effector along a vector of given length, maintaining current orientation.
void SetPowerConfig(bool aVal)
Power control.
void SetPosition(float aX, float aY, float aZ)
Move the end effector to a given position, ignoring orientation.
void SetBrakesConfig(bool aVal)
Brakes control.
LimbProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The LinuxjoystickProxy class is used to control a interface_joystick device.
Definition playerc++.h:1452
uint32_t GetAxesCount() const
Number of valid joystick poses.
Definition playerc++.h:1478
uint32_t GetButtons() const
return the sensor count
Definition playerc++.h:1468
double GetAxes(uint32_t aIndex) const
return a particular scan value
Definition playerc++.h:1471
The LocalizeProxy class is used to control a interface_localize device, which can provide multiple po...
Definition playerc++.h:1502
uint32_t GetNumHypoths() const
Get the number of localization hypoths.
Definition playerc++.h:1564
double GetMapScale() const
Map scale (m/cell)
Definition playerc++.h:1532
int GetParticles()
Get the particle set.
Definition playerc++.h:1554
void SetPose(double pose[3], double cov[6])
Set the current pose hypothesis (m, m, radians).
uint32_t GetMapTileX() const
Map tile X dimension (cells)
Definition playerc++.h:1527
uint32_t GetMapTileY() const
Map tile Y dimension (cells)
Definition playerc++.h:1529
uint32_t GetNumParticles() const
Get the number of particles (for particle filter-based localization systems).
Definition playerc++.h:1568
~LocalizeProxy()
Destructor.
uint32_t GetHypothCount() const
Number of possible poses.
Definition playerc++.h:1547
player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
Array of possible poses.
Definition playerc++.h:1550
uint32_t GetMapSizeX() const
Map X dimension (cells)
Definition playerc++.h:1521
uint32_t GetMapSizeY() const
Map Y dimension (cells)
Definition playerc++.h:1523
player_pose2d_t GetParticlePose(int index) const
Get the Pose of a particle.
LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
uint32_t GetPendingCount() const
Number of pending (unprocessed) sensor readings.
Definition playerc++.h:1544
The LogProxy proxy provides access to a interface_log device.
Definition playerc++.h:1576
void SetFilename(const std::string aFilename)
Set the name of the logfile to write to.
int GetType() const
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition playerc++.h:1594
int GetState() const
Is logging/playback enabled? Call QueryState() to fill it.
Definition playerc++.h:1597
void QueryState()
Query the server for type and state info.
LogProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void Rewind()
Rewind the log file.
~LogProxy()
Destructor.
void SetWriteState(int aState)
Start/stop (1/0) writing to the log file.
void SetReadState(int aState)
Start/stop (1/0) reading from the log file.
void SetState(int aState)
Start/stop (1/0) reading from or writing to the log file.
The map proxy provides access to a interface_map device.
Definition playerc++.h:1623
~MapProxy()
Destructor.
void RequestMap()
Get the map and store it in the proxy.
int8_t GetDataRange() const
Range of grid data (default: empty = -1, unknown = 0, occupied = +1)
Definition playerc++.h:1664
uint32_t GetWidth() const
Map size, in cells.
Definition playerc++.h:1655
MapProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
int8_t GetCell(int x, int y) const
Get the (x,y) cell.
Definition playerc++.h:1647
int GetCellIndex(int x, int y) const
Return the index of the (x,y) item in the cell array.
Definition playerc++.h:1643
void GetMap(int8_t *aMap) const
Occupancy for each cell.
Definition playerc++.h:1667
uint32_t GetHeight() const
Map size, in cells.
Definition playerc++.h:1658
double GetResolution() const
Map resolution, m/cell.
Definition playerc++.h:1651
The OpaqueProxy proxy provides an interface to a generic interface_opaque.
Definition playerc++.h:1681
void SendCmd(player_opaque_data_t *aData)
Send a command.
int SendReq(player_opaque_data_t *aRequest)
Send a request.
~OpaqueProxy()
Destructor.
uint32_t GetCount() const
How long is the data?
Definition playerc++.h:1699
void GetData(uint8_t *aDest) const
Opaque data.
Definition playerc++.h:1702
OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The PlannerProxy proxy provides an interface to a 2D motion interface_planner.
Definition playerc++.h:1721
void RequestWaypoints()
Get the list of waypoints.
double GetGy() const
Goal location (m)
Definition playerc++.h:1788
double GetGa() const
Goal location (radians)
Definition playerc++.h:1791
player_pose2d_t GetCurrentWaypoint() const
Get the current waypoint.
Definition playerc++.h:1815
~PlannerProxy()
Destructor.
uint32_t GetPathDone() const
Have we arrived at the goal?
Definition playerc++.h:1756
int GetCurrentWaypointId() const
Current waypoint index (handy if you already have the list of waypoints).
Definition playerc++.h:1850
double GetWx() const
Current waypoint location (m)
Definition playerc++.h:1806
double GetIa(int i) const
Grab a particular waypoint location (rad)
void SetStartPose(double aSx, double aSy, double aSa)
Set the start pose (sx, sy, sa)
player_pose2d_t GetWaypoint(uint32_t aIndex) const
Get the waypoint.
Definition playerc++.h:1836
player_pose2d_t GetPose() const
Get the current pose.
Definition playerc++.h:1773
double GetGx() const
Goal location (m)
Definition playerc++.h:1785
double GetIy(int i) const
Grab a particular waypoint location (m)
double GetPathLength() const
Get straight-line distance along path.
Definition playerc++.h:1760
PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
player_pose2d_t GetGoal() const
Get the goal.
Definition playerc++.h:1794
uint32_t GetPathValid() const
Did the planner find a valid path?
Definition playerc++.h:1753
double GetWy() const
Current waypoint location (m)
Definition playerc++.h:1809
double GetIx(int i) const
Grab a particular waypoint location (m)
double GetPa() const
Current pose (radians)
Definition playerc++.h:1770
void SetEnable(bool aEnable)
Enable/disable the robot's motion.
uint32_t GetWaypointCount() const
Number of waypoints in the plan.
Definition playerc++.h:1854
double GetPy() const
Current pose (m)
Definition playerc++.h:1767
double GetPx() const
Current pose (m)
Definition playerc++.h:1764
void SetGoalPose(double aGx, double aGy, double aGa)
Set the goal pose (gx, gy, ga)
double GetWa() const
Current waypoint location (rad)
Definition playerc++.h:1812
The PlayerClient is used for communicating with the player server.
Definition playerclient.h:121
The Pointcloud3d proxy provides an interface to a pointcloud3d device.
Definition playerc++.h:1870
player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const
return a particular scan value
Definition playerc++.h:1890
uint32_t GetCount() const
return the point count
Definition playerc++.h:1887
Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
The Position1dProxy class is used to control a interface_position1d device.
Definition playerc++.h:1905
void GoTo(double aPos, double aVel)
Send a motor command for position control mode.
double GetVel() const
Get current velocity.
Definition playerc++.h:1984
void SetSpeed(double aVel)
Send a motor command for velocity control mode.
bool IsOverCurrent() const
Is the device over current limits?
Definition playerc++.h:2008
bool IsTrajComplete() const
Is the device finished moving?
Definition playerc++.h:2013
Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
uint8_t GetStatus() const
Get device status.
Definition playerc++.h:1990
bool IsLimitMin() const
Is the device at the min limit?
Definition playerc++.h:1993
bool IsLimitMax() const
Is the device at the max limit?
Definition playerc++.h:2003
void SetMotorEnable(bool enable)
Enable/disable the motors.
double GetPos() const
Get current position.
Definition playerc++.h:1981
void ResetOdometry()
Reset odometry to 0.
Definition playerc++.h:1968
void RequestGeom()
Get the device's geometry; it is read into the relevant class attributes.
bool IsEnabled() const
Is the device enabled?
Definition playerc++.h:2018
void SetOdometry(double aPos)
Sets the odometry to the pose aPos.
bool GetStall() const
Get whether or not the device is stalled.
Definition playerc++.h:1987
player_bbox3d_t GetSize() const
Accessor for the size (fill it in by calling RequestGeom)
Definition playerc++.h:1948
player_pose3d_t GetPose() const
Accessor for the pose (fill it in by calling RequestGeom)
Definition playerc++.h:1937
~Position1dProxy()
Destructor.
bool IsLimitCen() const
Is the device at the center limit?
Definition playerc++.h:1998
The Position2dProxy class is used to control a interface_position2d device.
Definition playerc++.h:2029
void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
Send a motor command for velocity control mode.
void RequestGeom()
Get the device's geometry; it is read into the relevant class attributes.
void SetOdometry(double aX, double aY, double aYaw)
Sets the odometry to the pose (x, y, yaw).
bool GetStall() const
Is the device stalled?
Definition playerc++.h:2185
void GoTo(player_pose2d_t pos, player_pose2d_t vel)
Send a motor command for position control mode.
void SetMotorEnable(bool enable)
Enable/disable the motors.
double GetXPos() const
Get the device's X position.
Definition playerc++.h:2167
void GoTo(player_pose2d_t pos)
Same as the previous GoTo(), but doesn't take speed.
Definition playerc++.h:2077
double GetYaw() const
Get the device's Yaw position (angle)
Definition playerc++.h:2173
~Position2dProxy()
Destructor.
void SetVelHead(double aXSpeed, double aYawHead)
Same as the previous SetVelHead(), but doesn't take the yspeed speed (so use this one for non-holonom...
Definition playerc++.h:2067
void ResetOdometry()
Reset odometry to (0,0,0).
void SetCarlike(double aXSpeed, double aDriveAngle)
Sets command for carlike robot.
void SetSpeed(double aXSpeed, double aYawSpeed)
Same as the previous SetSpeed(), but doesn't take the yspeed speed (so use this one for non-holonomic...
Definition playerc++.h:2053
double GetYSpeed() const
Get the device's Y speed.
Definition playerc++.h:2179
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:2082
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition playerc++.h:2105
Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
double GetXSpeed() const
Get the device's X speed.
Definition playerc++.h:2176
double GetYPos() const
Get the device's Y position.
Definition playerc++.h:2170
player_pose3d_t GetOffset()
Accessor for the robot's pose with respect to its.
Definition playerc++.h:2094
void SetVelHead(double aXSpeed, double aYSpeed, double aYawHead)
Send a motor command for velocity/heading control mode.
double GetYawSpeed() const
Get the device's angular (yaw) speed.
Definition playerc++.h:2182
void SetSpeed(player_pose2d_t vel)
Overloaded SetSpeed that takes player_pose2d_t as an argument.
Definition playerc++.h:2057
The Position3dProxy class is used to control a interface_position3d device.
Definition playerc++.h:2196
double GetXSpeed() const
Get device X speed.
Definition playerc++.h:2314
void SelectVelocityControl(int aMode)
Select velocity control mode.
void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed, double aYawSpeed)
Send a motor command for a planar robot.
Definition playerc++.h:2222
void RequestGeom()
Get the device's geometry; it is read into the relevant class attributes.
void SetOdometry(double aX, double aY, double aZ, double aRoll, double aPitch, double aYaw)
Sets the odometry to the pose (x, y, z, roll, pitch, yaw).
double GetYaw() const
Get device Yaw angle.
Definition playerc++.h:2311
Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void GoTo(player_pose3d_t aPos, player_pose3d_t aVel)
Send a motor command for position control mode.
void SetSpeed(player_pose3d_t vel)
Overloaded SetSpeed that takes player_pose3d_t as input.
Definition playerc++.h:2236
void SetMotorEnable(bool aEnable)
Enable/disable the motors.
double GetXPos() const
Get device X position.
Definition playerc++.h:2296
void SetSpeed(double aXSpeed, double aYawSpeed)
Same as the previous SetSpeed(), but doesn't take the sideways speed (so use this one for non-holonom...
Definition playerc++.h:2232
double GetYawSpeed() const
Get device Yaw speed.
Definition playerc++.h:2329
void ResetOdometry()
Reset odometry to (0,0,0,0,0,0).
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:2251
~Position3dProxy()
Destructor.
void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed, double aRollSpeed, double aPitchSpeed, double aYawSpeed)
Send a motor command for a planar robot.
double GetRollSpeed() const
Get device Roll speed.
Definition playerc++.h:2323
double GetPitchSpeed() const
Get device Pitch speed.
Definition playerc++.h:2326
double GetYSpeed() const
Get device Y speed.
Definition playerc++.h:2317
double GetPitch() const
Get device Pitch angle.
Definition playerc++.h:2308
void GoTo(player_pose3d_t aPos)
Same as the previous GoTo(), but does'n take vel argument.
Definition playerc++.h:2245
double GetZSpeed() const
Get device Z speed.
Definition playerc++.h:2320
double GetRoll() const
Get device Roll angle.
Definition playerc++.h:2305
double GetYPos() const
Get device Y position.
Definition playerc++.h:2299
void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
simplified version of SetSpeed
Definition playerc++.h:2227
bool GetStall() const
Is the device stalled?
Definition playerc++.h:2332
double GetZPos() const
Get device Z position.
Definition playerc++.h:2302
The PowerProxy class controls a interface_power device.
Definition playerc++.h:2337
PowerProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
double GetPercent() const
Returns the percent of power.
Definition playerc++.h:2356
double GetJoules() const
Returns the joules.
Definition playerc++.h:2359
double GetCharge() const
Returns the current charge.
Definition playerc++.h:2353
bool GetCharging() const
Returns whether charging is taking place.
Definition playerc++.h:2365
~PowerProxy()
Destructor.
double GetWatts() const
Returns the watts.
Definition playerc++.h:2362
The PtzProxy class is used to control a interface_ptz device.
Definition playerc++.h:2378
int GetStatus()
Return Status.
double GetZoom() const
Return Zoom.
Definition playerc++.h:2413
double GetTilt() const
Return Tilt (rad)
Definition playerc++.h:2411
double GetPan() const
Return Pan (rad)
Definition playerc++.h:2409
void SetSpeed(double aPanSpeed=0, double aTiltSpeed=0, double aZoomSpeed=0)
Specify new target velocities.
void SetCam(double aPan, double aTilt, double aZoom)
Change the camera state.
void SelectControlMode(uint32_t aMode)
Select new control mode.
The RFIDProxy class is used to control a interface_rfid device.
Definition playerc++.h:2521
playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
returns a RFID tag
Definition playerc++.h:2540
RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
~RFIDProxy()
Destructor.
uint32_t GetTagsCount() const
returns the number of RFID tags
Definition playerc++.h:2538
The RangerProxy class is used to control a interface_ranger device.
Definition playerc++.h:2424
double GetIntensity(uint32_t aIndex) const
Get an intensity reading.
player_bbox3d_t GetDeviceSize() const
Return the device size.
Definition playerc++.h:2445
double GetAngularRes() const
Angular resolution of a scan (configured value)
Definition playerc++.h:2503
double GetMinAngle() const
Start angle of a scan (configured value)
Definition playerc++.h:2497
double GetRange(uint32_t aIndex) const
Get a range reading.
player_point_3d_t GetPoint(uint32_t aIndex) const
Get a point reading.
player_pose3d_t GetDevicePose() const
Return the device pose.
Definition playerc++.h:2443
void SetIntensityData(bool aEnable)
Turn intensity data on or off.
player_bbox3d_t GetElementSize(uint32_t aIndex) const
Return the size of an individual sensor.
void RequestConfigure()
Get the current ranger configuration; it is read into the relevant class attributes.
uint32_t GetPointCount() const
Return the number of point readings.
Definition playerc++.h:2460
uint32_t GetIntensityCount() const
Return the number of intensity readings.
Definition playerc++.h:2465
uint32_t GetElementCount() const
Return the individual range sensor count.
Definition playerc++.h:2440
double GetMaxAngle() const
Stop angle of a scan (configured value)
Definition playerc++.h:2500
RangerProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void SetPower(bool aEnable)
Turn the device power on or off.
uint32_t GetRangeCount() const
Return the number of range readings.
Definition playerc++.h:2453
~RangerProxy()
Destructor.
double GetMinRange() const
Minimum detectable range of a scan (configured value)
Definition playerc++.h:2506
double GetFrequency() const
Scanning frequency (configured value)
Definition playerc++.h:2515
double GetRangeRes() const
Linear resolution (configured value)
Definition playerc++.h:2512
double GetMaxRange() const
Maximum detectable range of a scan (configured value)
Definition playerc++.h:2509
player_pose3d_t GetElementPose(uint32_t aIndex) const
Return the pose of an individual sensor.
void Configure(double aMinAngle, double aMaxAngle, double aAngularRes, double aMinRange, double aMaxRange, double aRangeRes, double aFrequency)
Configure the ranger scan pattern.
void RequestGeom()
Request the ranger geometry.
The SimulationProxy proxy provides access to a interface_simulation device.
Definition playerc++.h:2556
SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void GetPose2d(char *identifier, double &x, double &y, double &a)
get the pose of an object in the simulator, identified by the std::string Returns 0 on success,...
void SetPose3d(char *identifier, double x, double y, double z, double roll, double pitch, double yaw)
set the 3D pose of an object in the simulator, identified by the std::string.
void GetPose3d(char *identifier, double &x, double &y, double &z, double &roll, double &pitch, double &yaw, double &time)
get the 3D pose of an object in the simulator, identified by the std::string Returns 0 on success,...
void GetProperty(char *identifier, char *name, void *value, size_t value_len)
Get a simulation property.
void SetPose2d(char *identifier, double x, double y, double a)
set the 2D pose of an object in the simulator, identified by the std::string.
~SimulationProxy()
Destructor.
void SetProperty(char *identifier, char *name, void *value, size_t value_len)
Set a simulation property.
The SonarProxy class is used to control a interface_sonar device.
Definition playerc++.h:2603
uint32_t GetPoseCount() const
Number of valid sonar poses.
Definition playerc++.h:2629
player_pose3d_t GetPose(uint32_t aIndex) const
Sonar poses (m,m,radians)
Definition playerc++.h:2632
~SonarProxy()
Destructor.
double GetScan(uint32_t aIndex) const
return a particular scan value
Definition playerc++.h:2622
uint32_t GetCount() const
return the sensor count
Definition playerc++.h:2619
SonarProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void RequestGeom()
Request the sonar geometry.
The SpeechProxy class is used to control a interface_speech device.
Definition playerc++.h:2651
~SpeechProxy()
Destructor.
SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void Say(std::string aStr)
Send a phrase to say.
The SpeechRecognition proxy provides access to a interface_speech_recognition device.
Definition playerc++.h:2676
SpeechRecognitionProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
std::string GetWord(uint32_t aWord) const
Accessor method for getting speech recognition data i.e. words.
Definition playerc++.h:2688
uint32_t GetCount(void) const
Gets the number of words.
Definition playerc++.h:2694
playerc_speechrecognition_t * mDevice
libplayerc data structure
Definition playerc++.h:2681
the Stereo proxy provides access to the interface_stereo device.
Definition playerc++.h:2705
uint32_t GetRightWidth() const
Right image width (pixels)
Definition playerc++.h:2762
void GetRightImage(uint8_t *aImage) const
Right image data This function copies the image data into the data buffer aImage.
Definition playerc++.h:2816
void DecompressLeft()
decompress the left image
Definition playerc++.h:2746
void SaveFrame(const std::string aPrefix, uint32_t aWidth, playerc_camera_t aDevice, uint8_t aIndex)
Save a frame.
uint32_t GetDisparityDepth() const
Disparity image color depth.
Definition playerc++.h:2757
void DecompressRight()
decompress the right image
Definition playerc++.h:2748
uint32_t GetDisparityCompression() const
Get the disparity image's compression type Currently supported compression types are:
Definition playerc++.h:2847
uint32_t GetLeftCompression() const
Get the left image's compression type Currently supported compression types are:
Definition playerc++.h:2837
uint32_t GetLeftWidth() const
Left image width (pixels)
Definition playerc++.h:2760
void GetLeftImage(uint8_t *aImage) const
Left image data This function copies the image data into the data buffer aImage.
Definition playerc++.h:2806
uint32_t GetRightCompression() const
Get the right image's compression type Currently supported compression types are:
Definition playerc++.h:2842
uint32_t GetRightDepth() const
Right image color depth.
Definition playerc++.h:2755
~StereoProxy()
Destructor.
uint32_t GetRightImageSize() const
Size of the right image (bytes)
Definition playerc++.h:2798
uint32_t GetLeftHeight() const
Left image height (pixels)
Definition playerc++.h:2767
uint32_t GetLeftFormat() const
Image format Possible values include.
Definition playerc++.h:2779
void GetDisparityImage(uint8_t *aImage) const
Disparity image data This function copies the image data into the data buffer aImage.
Definition playerc++.h:2826
void Decompress(playerc_camera_t aDevice)
Decompress an image.
void SaveRightFrame(const std::string aPrefix, uint32_t aWidth=4)
Save the right frame.
Definition playerc++.h:2739
void SaveDisparityFrame(const std::string aPrefix, uint32_t aWidth=4)
Save the disparity frame.
Definition playerc++.h:2743
uint32_t GetRightFormat() const
Image format Possible values include.
Definition playerc++.h:2786
uint32_t GetCount() const
return the point count
Definition playerc++.h:2850
playerc_stereo_t * mDevice
libplayerc data structure
Definition playerc++.h:2711
uint32_t GetLeftImageSize() const
Size of the left image (bytes)
Definition playerc++.h:2796
uint32_t GetDisparityWidth() const
Disparity image width (pixels)
Definition playerc++.h:2764
StereoProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
std::string mPrefix
Default image prefix.
Definition playerc++.h:2720
player_pointcloud3d_stereo_element_t GetPoint(uint32_t aIndex) const
return a particular point value
Definition playerc++.h:2853
uint32_t GetRightHeight() const
Right image height (pixels)
Definition playerc++.h:2769
uint32_t GetDisparityFormat() const
Image format Possible values include.
Definition playerc++.h:2793
uint32_t GetDisparityImageSize() const
Size of the disparity image (bytes)
Definition playerc++.h:2800
uint32_t GetLeftDepth() const
Left image color depth.
Definition playerc++.h:2753
uint32_t GetDisparityHeight() const
Disparity image height (pixels)
Definition playerc++.h:2771
void DecompressDisparity()
decompress the disparity image
Definition playerc++.h:2750
void SaveLeftFrame(const std::string aPrefix, uint32_t aWidth=4)
Save the left frame.
Definition playerc++.h:2735
The VectorMapProxy class is used to interface to a vectormap.
Definition playerc++.h:2866
~VectorMapProxy()
Destructor.
size_t GetFeatureDataCount(unsigned layer_index, unsigned feature_index) const
Get how long the feature data is for a layer and feature.
VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
int GetFeatureCount(unsigned layer_index) const
Get how many features are in a particular layer.
const uint8_t * GetFeatureData(unsigned layer_index, unsigned feature_index) const
Get the feature data for a layer and feature.
int GetLayerCount() const
Get how many layers are in the map.
void GetMapInfo()
Request map information from the underlying device.
std::vector< std::string > GetLayerNames() const
Get the names of each of the layers.
void GetLayerData(unsigned layer_index)
Request data for a specific layer from the underlying device.
The WSNProxy class is used to control a interface_wsn device.
Definition playerc++.h:2957
WSNProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
void DataType(int value)
Set WSN device type.
void DataFreq(int nodeID, int groupID, float frequency)
Set WSN device frequency.
void SetDevState(int nodeID, int groupID, int devNr, int value)
Set a WSN device State.
uint32_t GetNodeType() const
Get the node's type.
Definition playerc++.h:2974
uint32_t GetNodeID() const
Get the node's ID.
Definition playerc++.h:2976
void Power(int nodeID, int groupID, int value)
Set WSN device Power.
player_wsn_node_data_t GetNodeDataPacket() const
Get a WSN node packet.
Definition playerc++.h:2982
uint32_t GetNodeParentID() const
Get the node's parent ID.
Definition playerc++.h:2978
~WSNProxy()
Destructor.
The WiFiProxy class controls a interface_wifi device.
Definition playerc++.h:2910
char * GetOwnIP() const
Get your current IP address.
Definition playerc++.h:2932
char * GetLinkESSID(int index) const
Get the ESSID from a particular link.
Definition playerc++.h:2938
double GetLinkFreq(int index) const
Get the frequency from a particular link.
Definition playerc++.h:2940
int GetLinkEncrypt(int index) const
Get whether a particular link is encrypted.
Definition playerc++.h:2944
int GetLinkCount() const
Get how many links the device sees.
Definition playerc++.h:2930
char * GetLinkMAC(int index) const
Get the MAC address from a particular link.
Definition playerc++.h:2936
const playerc_wifi_link_t * GetLink(int aLink)
Get the playerc wifi link data.
int GetLinkMode(int index) const
Get the connection mode from a particular link.
Definition playerc++.h:2942
int GetLinkLevel(int index) const
Get the signal level of a particular link.
Definition playerc++.h:2948
int GetLinkNoise(int index) const
Get the noise level of a particular link.
Definition playerc++.h:2950
~WiFiProxy()
Destructor.
int GetLinkQuality(int index) const
Get the quality of a particular link.
Definition playerc++.h:2946
WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0)
Constructor.
char * GetLinkIP(int index) const
Get the IP address from a particular link.
Definition playerc++.h:2934
Definition playerclient.h:96
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
A rectangular bounding box, used to define the size of an object.
Definition player.h:246
A rectangular bounding box, used to define the size of an object.
Definition player.h:255
double sw
Width [m].
Definition player.h:257
double sl
Length [m].
Definition player.h:259
Vectormap feature data.
Definition player.h:266
A color descriptor.
Definition player.h:321
A rectangular bounding box, used to define the origin and bounds of an object.
Definition player.h:308
An angle in 3D space.
Definition player.h:207
A point in the plane.
Definition player.h:185
A point in 3D space.
Definition player.h:195
A pose in the plane.
Definition player.h:218
double px
X [m].
Definition player.h:220
double pa
yaw [rad]
Definition player.h:224
double py
Y [m].
Definition player.h:222
A pose in space.
Definition player.h:229
double pz
Z [m].
Definition player.h:235
double py
Y [m].
Definition player.h:233
double ppitch
pitch [rad]
Definition player.h:239
double px
X [m].
Definition player.h:231
double pyaw
yaw [rad]
Definition player.h:241
double proll
roll [rad]
Definition player.h:237
A line segment, used to construct vector-based maps.
Definition player.h:292
Actarray device data.
Definition playerc.h:1037
player_orientation_3d_t base_orientation
The orientation of the base of the actarray.
Definition playerc.h:1053
uint32_t actuators_count
The number of actuators in the array.
Definition playerc.h:1042
player_point_3d_t base_pos
The position of the base of the actarray.
Definition playerc.h:1051
Aio proxy data.
Definition playerc.h:980
Audio device data.
Definition playerc.h:1131
player_audio_seq_t seq_data
last block of seq data
Definition playerc.h:1142
player_audio_mixer_channel_list_detail_t channel_details_list
Details of the channels from the mixer.
Definition playerc.h:1136
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition playerc.h:1145
uint32_t state
current driver state
Definition playerc.h:1148
player_audio_wav_t wav_data
last block of recorded data
Definition playerc.h:1139
BlackBoard proxy.
Definition playerc.h:1229
Blobfinder device data.
Definition playerc.h:1346
unsigned int blobs_count
A list of detected blobs.
Definition playerc.h:1354
unsigned int width
Image dimensions (pixels).
Definition playerc.h:1351
Bumper proxy data.
Definition playerc.h:1389
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition playerc.h:1405
int bumper_count
Number of points in the scan.
Definition playerc.h:1402
int pose_count
Number of pose values.
Definition playerc.h:1394
player_bumper_define_t * poses
Pose of each bumper relative to robot (mm, mm, deg, mm, mm).
Definition playerc.h:1399
Camera proxy data.
Definition playerc.h:1446
int image_count
Size of image data (bytes)
Definition playerc.h:1468
uint8_t * image
Image data (byte aligned, row major order).
Definition playerc.h:1474
int bpp
Image bits-per-pixel (8, 16, 24).
Definition playerc.h:1454
int width
Image dimensions (pixels).
Definition playerc.h:1451
int format
Image format (e.g., RGB888).
Definition playerc.h:1457
int compression
Image compression method.
Definition playerc.h:1465
Note: the structure describing the Cooperating Object's data packet is declared in Player.
Definition playerc.h:1533
uint8_t command
Command type.
Definition playerc.h:1582
uint8_t * user_data
User defined data array.
Definition playerc.h:1579
uint32_t sensor_data_count
Number of sensors included.
Definition playerc.h:1568
uint32_t user_data_count
User defined message size (in bytes)
Definition playerc.h:1577
int messageType
Flag to indicate that new info has come.
Definition playerc.h:1538
uint32_t alarm_data_count
Number of alarms included.
Definition playerc.h:1572
player_coopobject_sensor_t * alarm_data
Active alarms array.
Definition playerc.h:1574
uint16_t id
Cooperating Object ID.
Definition playerc.h:1547
uint16_t RSSIsender
Cooperating Object data packet.
Definition playerc.h:1554
uint8_t request
Request type.
Definition playerc.h:1584
uint8_t * parameters
Request/command parameters array
Definition playerc.h:1588
float x
Cooperating Object Position.
Definition playerc.h:1561
uint16_t parent_id
Cooperating Object Parent ID (if existing)
Definition playerc.h:1549
uint8_t origin
The type of Cooperating Object.
Definition playerc.h:1545
uint32_t parameters_count
Request/command parameters array size (in bytes)
Definition playerc.h:1586
player_coopobject_sensor_t * sensor_data
Sensor measurements array.
Definition playerc.h:1570
Info about an available (but not necessarily subscribed) device.
Definition playerc.h:496
Dio proxy data.
Definition playerc.h:1640
Fiducial finder data.
Definition playerc.h:1689
player_fiducial_geom_t fiducial_geom
Geometry in robot cs.
Definition playerc.h:1697
int fiducials_count
List of detected beacons.
Definition playerc.h:1700
GPS proxy data.
Definition playerc.h:1742
double hdop
Horizontal dilution of precision.
Definition playerc.h:1769
double err_horz
Horizontal and vertical error (meters).
Definition playerc.h:1775
int sat_count
Number of satellites in view.
Definition playerc.h:1781
double speed
Speed over ground, in m/s.
Definition playerc.h:1759
double course
Course made good (heading if the robot moves along its longitudinal axis), in radians.
Definition playerc.h:1763
double alt
Altitude (meters).
Definition playerc.h:1756
double utm_e
UTM easting and northing (meters).
Definition playerc.h:1766
double vdop
Vertical dilution of precision.
Definition playerc.h:1772
double lat
Latitude and logitude (degrees).
Definition playerc.h:1752
int quality
Quality of fix 0 = invalid, 1 = GPS fix, 2 = DGPS fix.
Definition playerc.h:1778
double utc_time
UTC time (seconds since the epoch)
Definition playerc.h:1747
Graphics2d device data.
Definition playerc.h:1813
Graphics3d device data.
Definition playerc.h:1880
Gripper device data.
Definition playerc.h:1936
uint8_t capacity
The capacity of the gripper's store - if 0, the gripper cannot store.
Definition playerc.h:1952
uint8_t num_beams
The number of breakbeams the gripper has.
Definition playerc.h:1950
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition playerc.h:1946
uint8_t stored
The number of currently-stored objects.
Definition playerc.h:1961
uint8_t state
The gripper's state: may be one of PLAYER_GRIPPER_STATE_OPEN, PLAYER_GRIPPER_STATE_CLOSED,...
Definition playerc.h:1957
uint32_t beams
The position of the object in the gripper.
Definition playerc.h:1959
Note: the structure describing the HEALTH's data packet is declared in Player.
Definition playerc.h:2019
IMU proxy state data.
Definition playerc.h:3771
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition playerc.h:3781
player_pose3d_t pose
The complete pose of the IMU in 3D coordinates + angles
Definition playerc.h:3776
Ir proxy data.
Definition playerc.h:2060
joystick proxy data.
Definition playerc.h:2109
Laser proxy data.
Definition playerc.h:2154
int * intensity
Scan reflection intensity values (0-3).
Definition playerc.h:2200
player_point_2d_t * point
Scan data; x, y position (m).
Definition playerc.h:2195
double range_res
Range resolution, in m.
Definition playerc.h:2180
double(* scan)[2]
Scan data; range (m) and bearing (radians).
Definition playerc.h:2192
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam,...
Definition playerc.h:2211
int scan_count
Number of points in the scan.
Definition playerc.h:2171
double max_range
Maximum range of sensor, in m.
Definition playerc.h:2183
double * ranges
Raw range data; range (m).
Definition playerc.h:2189
int intensity_on
Is intesity data returned.
Definition playerc.h:2168
double scan_res
Angular resolution in radians.
Definition playerc.h:2177
double min_left
Minimum range, in meters, in the left half of the scan (those ranges from the first beam after the mi...
Definition playerc.h:2216
double scan_start
Start bearing of the scan (radians).
Definition playerc.h:2174
double pose[3]
Laser geometry in the robot cs: pose gives the position and orientation, size gives the extent.
Definition playerc.h:2161
double robot_pose[3]
Robot pose (m,m,rad), filled in if the scan came with a pose attached.
Definition playerc.h:2165
double scanning_frequency
Scanning frequency in Hz.
Definition playerc.h:2186
int laser_id
Laser IDentification information.
Definition playerc.h:2206
Limb device data.
Definition playerc.h:2326
Localization device data.
Definition playerc.h:2408
double map_scale
Map scale (m/cell).
Definition playerc.h:2416
int pending_count
The number of pending (unprocessed) sensor readings.
Definition playerc.h:2425
int map_size_x
Map dimensions (cells).
Definition playerc.h:2413
int map_tile_x
Next map tile to read.
Definition playerc.h:2419
int hypoth_count
List of possible poses.
Definition playerc.h:2431
Log proxy data.
Definition playerc.h:2476
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition playerc.h:2482
int state
Is logging/playback enabled? Call playerc_log_get_state() to fill it.
Definition playerc.h:2486
Map proxy data.
Definition playerc.h:2536
double origin[2]
Map origin, in meters (i.e., the real-world coordinates of cell 0,0)
Definition playerc.h:2547
char * cells
Occupancy for each cell.
Definition playerc.h:2553
int8_t data_range
Value for each cell (-range <= EMPTY < 0, unknown = 0, 0 < OCCUPIED <= range)
Definition playerc.h:2550
double resolution
Map resolution, m/cell.
Definition playerc.h:2541
int width
Map size, in cells.
Definition playerc.h:2544
Opaque device data.
Definition playerc.h:2657
int data_count
Size of data (bytes)
Definition playerc.h:2662
uint8_t * data
Data
Definition playerc.h:2665
Planner device data.
Definition playerc.h:2706
double wx
Current waypoint location (m, m, radians)
Definition playerc.h:2723
double(* waypoints)[3]
List of waypoints in the current plan (m,m,radians).
Definition playerc.h:2735
double px
Current pose (m, m, radians).
Definition playerc.h:2717
double waypoint_distance
Straight-line distance along allwaypoints in the current plan.
Definition playerc.h:2739
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition playerc.h:2728
int waypoint_count
Number of waypoints in the plan.
Definition playerc.h:2731
int path_valid
Did the planner find a valid path?
Definition playerc.h:2711
double gx
Goal location (m, m, radians)
Definition playerc.h:2720
int path_done
Have we arrived at the goal?
Definition playerc.h:2714
pointcloud3d proxy data.
Definition playerc.h:3686
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition playerc.h:3694
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition playerc.h:3691
Position1d device data.
Definition playerc.h:2793
double vel
Odometric velocity [m/s] or [rad/s].
Definition playerc.h:2807
double pos
Odometric pose [m] or [rad].
Definition playerc.h:2804
int status
Status bitfield of extra data in the following order:
Definition playerc.h:2823
int stall
Stall flag [0, 1].
Definition playerc.h:2810
double pose[3]
Robot geometry in robot cs: pose gives the position1d and orientation, size gives the extent.
Definition playerc.h:2800
Position2d device data.
Definition playerc.h:2887
double pose[3]
Robot geometry in robot cs: pose gives the position2d and orientation, size gives the extent.
Definition playerc.h:2894
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition playerc.h:2901
int stall
Stall flag [0, 1].
Definition playerc.h:2904
double px
Odometric pose (m, m, rad).
Definition playerc.h:2898
Position3d device data.
Definition playerc.h:2982
double vel_roll
Angular velocity (radians/sec).
Definition playerc.h:3002
double pos_roll
Device orientation (radians).
Definition playerc.h:2996
double pos_x
Device position (m).
Definition playerc.h:2993
int stall
Stall flag [0, 1].
Definition playerc.h:3005
double vel_x
Linear velocity (m/s).
Definition playerc.h:2999
Power device data.
Definition playerc.h:3086
int valid
status bits.
Definition playerc.h:3092
double watts
power currently being used (Watts).
Definition playerc.h:3105
double percent
Battery charge (percent full).
Definition playerc.h:3098
double charge
Battery charge (Volts).
Definition playerc.h:3095
int charging
charging flag.
Definition playerc.h:3108
double joules
energy stored (Joules)
Definition playerc.h:3101
PTZ device data.
Definition playerc.h:3143
double zoom
The current zoom value (field of view angle).
Definition playerc.h:3153
double pan
The current ptz pan and tilt angles.
Definition playerc.h:3150
Ranger proxy data.
Definition playerc.h:3225
uint32_t intensities_count
Number of intensities in a scan.
Definition playerc.h:3265
uint32_t element_count
Number of individual elements in the device.
Definition playerc.h:3230
player_pose3d_t device_pose
Device geometry in the robot CS: pose gives the position and orientation, size gives the extent.
Definition playerc.h:3251
double range_res
Range resolution [m].
Definition playerc.h:3244
double max_range
Maximum range [m].
Definition playerc.h:3242
double max_angle
End angle of scans [rad].
Definition playerc.h:3235
uint32_t points_count
Number of scan points.
Definition playerc.h:3278
uint32_t ranges_count
Number of ranges in a scan.
Definition playerc.h:3260
double min_range
Minimum range [m].
Definition playerc.h:3240
double angular_res
Scan resolution [rad].
Definition playerc.h:3237
double frequency
Scanning frequency [Hz].
Definition playerc.h:3246
double min_angle
Start angle of scans [rad].
Definition playerc.h:3233
RFID proxy data.
Definition playerc.h:3645
uint16_t tags_count
The number of RFID tags found.
Definition playerc.h:3650
playerc_rfidtag_t * tags
The list of RFID tags.
Definition playerc.h:3653
Structure describing a single RFID tag.
Definition playerc.h:3634
Simulation device proxy.
Definition playerc.h:3484
Sonar proxy data.
Definition playerc.h:3359
int scan_count
Number of points in the scan.
Definition playerc.h:3371
int pose_count
Number of pose values.
Definition playerc.h:3364
player_pose3d_t * poses
Pose of each sonar relative to robot (m, m, radians).
Definition playerc.h:3368
double * scan
Scan data: range (m).
Definition playerc.h:3374
Speech proxy data.
Definition playerc.h:3560
Speech recognition proxy data.
Definition playerc.h:3596
stereo proxy data.
Definition playerc.h:3726
Vectormap proxy.
Definition playerc.h:2596
Wifi device proxy.
Definition playerc.h:3441
playerc_wifi_link_t * links
A list containing info for each link.
Definition playerc.h:3446
Note: the structure describing the WSN node's data packet is declared in Player.
Definition playerc.h:3825
player_wsn_node_data_t data_packet
The WSN node's data packet.
Definition playerc.h:3836
uint32_t node_id
The ID of the WSN node.
Definition playerc.h:3832
uint32_t node_parent_id
The ID of the WSN node's parent (if existing).
Definition playerc.h:3834
uint32_t node_type
The type of WSN node.
Definition playerc.h:3830