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"
67 #if defined (PLAYER_STATIC)
68 #define PLAYERCC_EXPORT
69 #elif defined (playerc___EXPORTS)
70 #define PLAYERCC_EXPORT __declspec (dllexport)
72 #define PLAYERCC_EXPORT __declspec (dllimport)
75 #define PLAYERCC_EXPORT
141 class PLAYERCC_EXPORT ActArrayProxy :
public ClientProxy
145 void Subscribe(uint32_t aIndex);
154 ActArrayProxy(PlayerClient *aPc, uint32_t aIndex=0);
160 void RequestGeometry(
void);
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);
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);
187 uint32_t GetCount(
void)
const {
return GetVar(mDevice->
actuators_count); }
203 {
return(GetActuatorData(aJoint)); }
209 class PLAYERCC_EXPORT AioProxy :
public ClientProxy
213 void Subscribe(uint32_t aIndex);
222 AioProxy (PlayerClient *aPc, uint32_t aIndex=0);
227 uint32_t GetCount()
const {
return(GetVar(mDevice->voltages_count)); };
230 double GetVoltage(uint32_t aIndex)
const
231 {
return(GetVar(mDevice->voltages[aIndex])); };
234 void SetVoltage(uint32_t aIndex,
double aVoltage);
240 double operator [](uint32_t aIndex)
const
241 {
return GetVoltage(aIndex); }
249 class PLAYERCC_EXPORT AudioProxy :
public ClientProxy
254 void Subscribe(uint32_t aIndex);
263 AudioProxy(PlayerClient *aPc, uint32_t aIndex=0);
282 void GetWavData(uint8_t* aData)
const
299 uint32_t GetState(
void)
const {
return(GetVar(mDevice->
state));};
304 void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
307 void SetWavStremRec(
bool aState);
310 void PlaySample(
int aIndex);
319 void SetMixerLevel(uint32_t index,
float amplitude, uint8_t active);
326 void LoadSample(
int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
330 void GetSample(
int aIndex);
333 void RecordSample(
int aIndex, uint32_t aLength);
337 void GetMixerLevels();
341 void GetMixerDetails();
352 class PLAYERCC_EXPORT BlackBoardProxy :
public ClientProxy
355 void Subscribe(uint32_t aIndex);
363 BlackBoardProxy(PlayerClient *aPc, uint32_t aIndex=0);
369 void UnsubscribeFromKey(
const char *key,
const char* group =
"");
371 void SubscribeToGroup(
const char* key);
373 void UnsubscribeFromGroup(
const char* group);
425 class PLAYERCC_EXPORT BlobfinderProxy :
public ClientProxy
429 void Subscribe(uint32_t aIndex);
437 BlobfinderProxy(PlayerClient *aPc, uint32_t aIndex=0);
442 uint32_t GetCount()
const {
return GetVar(mDevice->
blobs_count); };
445 {
return GetVar(mDevice->blobs[aIndex]);};
448 uint32_t GetWidth()
const {
return GetVar(mDevice->
width); };
450 uint32_t GetHeight()
const {
return GetVar(mDevice->height); };
457 {
return(GetBlob(aIndex)); }
476 class PLAYERCC_EXPORT BumperProxy :
public ClientProxy
481 void Subscribe(uint32_t aIndex);
490 BumperProxy(PlayerClient *aPc, uint32_t aIndex=0);
495 uint32_t GetCount()
const {
return GetVar(mDevice->
bumper_count); };
498 uint32_t IsBumped(uint32_t aIndex)
const
499 {
return GetVar(mDevice->
bumpers[aIndex]); };
505 void RequestBumperConfig();
508 uint32_t GetPoseCount()
const {
return GetVar(mDevice->
pose_count); };
512 {
return GetVar(mDevice->
poses[aIndex]); };
518 bool operator [](uint32_t aIndex)
const
519 {
return IsBumped(aIndex) != 0 ? true :
false; }
526 class PLAYERCC_EXPORT CameraProxy :
public ClientProxy
531 virtual void Subscribe(uint32_t aIndex);
532 virtual void Unsubscribe();
543 CameraProxy (PlayerClient *aPc, uint32_t aIndex=0);
546 virtual ~CameraProxy();
551 void SaveFrame(
const std::string aPrefix, uint32_t aWidth=4);
557 uint32_t GetDepth()
const {
return GetVar(mDevice->
bpp); };
560 uint32_t GetWidth()
const {
return GetVar(mDevice->
width); };
563 uint32_t GetHeight()
const {
return GetVar(mDevice->height); };
571 uint32_t GetFormat()
const {
return GetVar(mDevice->
format); };
574 uint32_t GetImageSize()
const {
return GetVar(mDevice->
image_count); };
580 void GetImage(uint8_t* aImage)
const
582 return GetVarByRef(mDevice->
image,
591 uint32_t GetCompression()
const {
return GetVar(mDevice->
compression); };
598 class PLAYERCC_EXPORT CoopObjectProxy :
public ClientProxy
603 void Subscribe(uint32_t aIndex);
613 CoopObjectProxy(PlayerClient *aPc, uint32_t aIndex = 0);
628 int MessageType ()
const {
return GetVar(mDevice->
messageType); };
636 uint32_t GetOrigin ()
const {
return GetVar(mDevice->
origin); };
639 uint32_t GetID ()
const {
return GetVar(mDevice->
id); };
642 uint32_t GetParentID()
const {
return GetVar(mDevice->
parent_id); };
645 uint32_t GetProxyID ()
const {
return id; };
648 void SetProxyID (uint32_t value) {
id = value; };
651 uint32_t GetSensorNumber ()
const {
return GetVar(mDevice->
sensor_data_count); };
672 uint8_t GetSensorType (uint32_t index)
const {
if ( index < GetSensorNumber() )
return GetVar(mDevice->
sensor_data[index].
type);
else return -1; };
675 uint16_t GetSensorData (uint32_t index)
const {
if ( index < GetSensorNumber() )
return GetVar(mDevice->
sensor_data[index].
value);
else return -1; };
678 uint32_t GetAlarmNumber ()
const {
return GetVar(mDevice->
alarm_data_count); };
701 uint8_t GetAlarmType (uint32_t index)
const {
if ( index < GetAlarmNumber() )
return GetVar(mDevice->
alarm_data[index].
type);
else return -1; };
704 uint16_t GetAlarmData (uint32_t index)
const {
if ( index < GetAlarmNumber() )
return GetVar(mDevice->
alarm_data[index].
value);
else return -1; };
707 uint32_t GetUserDataNumber ()
const {
return GetVar(mDevice->
user_data_count); };
710 uint8_t *GetAllUserData ()
const {
return GetVar(mDevice->
user_data); };
713 uint8_t GetUserData (uint32_t index)
const {
if ( index < GetUserDataNumber() )
return GetVar(mDevice->
user_data[index]);
else return 0xFF; };
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); };
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); };
734 uint32_t GetRequest ()
const {
return GetVar(mDevice->
request); };
736 uint32_t GetCommand ()
const {
return GetVar(mDevice->
command); };
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; };
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);
765 class PLAYERCC_EXPORT DioProxy :
public ClientProxy
769 void Subscribe(uint32_t aIndex);
777 DioProxy(PlayerClient *aPc, uint32_t aIndex=0);
782 uint32_t GetCount()
const {
return GetVar(mDevice->count); };
785 uint32_t GetDigin()
const {
return GetVar(mDevice->digin); };
788 bool GetInput(uint32_t aIndex)
const;
791 void SetOutput(uint32_t aCount, uint32_t aDigout);
797 uint32_t operator [](uint32_t aIndex)
const
798 {
return GetInput(aIndex); }
806 class PLAYERCC_EXPORT FiducialProxy :
public ClientProxy
809 void Subscribe(uint32_t aIndex);
817 FiducialProxy(PlayerClient *aPc, uint32_t aIndex=0);
822 uint32_t GetCount()
const {
return GetVar(mDevice->
fiducials_count); };
826 {
return GetVar(mDevice->fiducials[aIndex]);};
841 void RequestGeometry();
848 {
return GetFiducialItem(aIndex); }
854 class PLAYERCC_EXPORT GpsProxy :
public ClientProxy
859 void Subscribe(uint32_t aIndex);
868 GpsProxy(PlayerClient *aPc, uint32_t aIndex=0);
873 double GetLatitude()
const {
return GetVar(mDevice->
lat); };
874 double GetLongitude()
const {
return GetVar(mDevice->lon); };
877 double GetAltitude()
const {
return GetVar(mDevice->
alt); };
880 double GetSpeed()
const {
return GetVar(mDevice->
speed); };
884 double GetCourse()
const {
return GetVar(mDevice->
course); };
887 uint32_t GetSatellites()
const {
return GetVar(mDevice->
sat_count); };
890 uint32_t GetQuality()
const {
return GetVar(mDevice->
quality); };
893 double GetHdop()
const {
return GetVar(mDevice->
hdop); };
896 double GetVdop()
const {
return GetVar(mDevice->
vdop); };
899 double GetUtmEasting()
const {
return GetVar(mDevice->
utm_e); };
900 double GetUtmNorthing()
const {
return GetVar(mDevice->utm_n); };
903 double GetTime()
const {
return GetVar(mDevice->
utc_time); };
906 double GetErrHorizontal()
const {
return GetVar(mDevice->
err_horz); };
907 double GetErrVertical()
const {
return GetVar(mDevice->err_vert); };
917 class PLAYERCC_EXPORT Graphics2dProxy :
public ClientProxy
923 void Subscribe(uint32_t aIndex);
932 Graphics2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
940 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
967 class PLAYERCC_EXPORT Graphics3dProxy :
public ClientProxy
973 void Subscribe(uint32_t aIndex);
982 Graphics3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
990 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
1004 class PLAYERCC_EXPORT GripperProxy :
public ClientProxy
1009 void Subscribe(uint32_t aIndex);
1018 GripperProxy(PlayerClient *aPc, uint32_t aIndex=0);
1024 void RequestGeometry(
void);
1027 uint32_t GetState()
const {
return GetVar(mDevice->
state); };
1029 uint32_t GetBeams()
const {
return GetVar(mDevice->
beams); };
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); };
1057 class PLAYERCC_EXPORT HealthProxy :
public ClientProxy
1062 void Subscribe(uint32_t aIndex);
1070 HealthProxy(PlayerClient *aPc, uint32_t aIndex=0);
1078 float GetSystemCPU();
1084 int64_t GetMemTotal();
1087 int64_t GetMemUsed();
1090 int64_t GetMemFree();
1093 int64_t GetSwapTotal();
1096 int64_t GetSwapUsed();
1099 int64_t GetSwapFree();
1102 float GetPercMemUsed();
1105 float GetPercSwapUsed();
1108 float GetPercTotalUsed();
1117 class PLAYERCC_EXPORT ImuProxy :
public ClientProxy
1120 void Subscribe(uint32_t aIndex);
1129 ImuProxy(PlayerClient *aPc, uint32_t aIndex=0);
1160 void SetDatatype(
int aDatatype);
1163 void ResetOrientation(
int aValue);
1166 void ResetEuler(
float aRoll,
float aPitch,
float aYaw);
1175 class PLAYERCC_EXPORT IrProxy :
public ClientProxy
1180 void Subscribe(uint32_t aIndex);
1189 IrProxy(PlayerClient *aPc, uint32_t aIndex=0);
1196 double GetRange(uint32_t aIndex)
const
1197 {
return GetVar(mDevice->data.
ranges[aIndex]); };
1199 double GetVoltage(uint32_t aIndex)
const
1202 uint32_t GetPoseCount()
const {
return GetVar(mDevice->poses.
poses_count); };
1205 {
return GetVar(mDevice->poses.
poses[aIndex]);};
1214 double operator [](uint32_t aIndex)
const
1215 {
return GetRange(aIndex); }
1224 class PLAYERCC_EXPORT LaserProxy :
public ClientProxy
1228 void Subscribe(uint32_t aIndex);
1235 double min_angle, max_angle, scan_res, range_res, scanning_frequency;
1241 LaserProxy(PlayerClient *aPc, uint32_t aIndex=0);
1246 uint32_t GetCount()
const {
return GetVar(mDevice->
scan_count); };
1249 double GetMaxRange()
const {
return GetVar(mDevice->
max_range); };
1252 double GetScanRes()
const {
return GetVar(mDevice->
scan_res); };
1255 double GetRangeRes()
const {
return GetVar(mDevice->
range_res); };
1261 double GetMinAngle()
const {
return GetVar(mDevice->
scan_start); };
1263 double GetMaxAngle()
const
1265 scoped_lock_t lock(mPc->mMutex);
1270 double GetConfMinAngle()
const {
return min_angle; };
1272 double GetConfMaxAngle()
const {
return max_angle; };
1275 bool IntensityOn()
const {
return GetVar(mDevice->
intensity_on) != 0 ? true :
false; };
1283 {
return GetVar(mDevice->
point[aIndex]); };
1287 double GetRange(uint32_t aIndex)
const
1288 {
return GetVar(mDevice->
ranges[aIndex]); };
1291 double GetBearing(uint32_t aIndex)
const
1292 {
return GetVar(mDevice->
scan[aIndex][1]); };
1296 int GetIntensity(uint32_t aIndex)
const
1297 {
return GetVar(mDevice->
intensity[aIndex]); };
1301 {
return GetVar(mDevice->
laser_id); };
1312 void Configure(
double aMinAngle,
1317 double aScanningFrequency);
1321 void RequestConfigure();
1335 scoped_lock_t lock(mPc->mMutex);
1348 scoped_lock_t lock(mPc->mMutex);
1362 b.
sl = mDevice->size[0];
1363 b.
sw = mDevice->size[1];
1368 double GetMinLeft()
const
1369 {
return GetVar(mDevice->
min_left); };
1372 double GetMinRight()
const
1376 double MinLeft ()
const
1377 {
return GetMinLeft(); }
1380 double MinRight ()
const
1381 {
return GetMinRight(); }
1387 double operator [] (uint32_t index)
const
1388 {
return GetRange(index);}
1397 class PLAYERCC_EXPORT LimbProxy :
public ClientProxy
1401 void Subscribe(uint32_t aIndex);
1410 LimbProxy(PlayerClient *aPc, uint32_t aIndex=0);
1416 void RequestGeometry(
void);
1419 void SetPowerConfig(
bool aVal);
1421 void SetBrakesConfig(
bool aVal);
1423 void SetSpeedConfig(
float aSpeed);
1426 void MoveHome(
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);
1451 class PLAYERCC_EXPORT LinuxjoystickProxy :
public ClientProxy
1455 void Subscribe(uint32_t aIndex);
1463 LinuxjoystickProxy(PlayerClient *aPc, uint32_t aIndex=0);
1465 ~LinuxjoystickProxy();
1468 uint32_t GetButtons()
const {
return GetVar(mDevice->buttons); };
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); }
1478 uint32_t GetAxesCount()
const {
return GetVar(mDevice->axes_count); };
1501 class PLAYERCC_EXPORT LocalizeProxy :
public ClientProxy
1506 void Subscribe(uint32_t aIndex);
1515 LocalizeProxy(PlayerClient *aPc, uint32_t aIndex=0);
1521 uint32_t GetMapSizeX()
const {
return GetVar(mDevice->
map_size_x); };
1523 uint32_t GetMapSizeY()
const {
return GetVar(mDevice->map_size_y); };
1527 uint32_t GetMapTileX()
const {
return GetVar(mDevice->
map_tile_x); };
1529 uint32_t GetMapTileY()
const {
return GetVar(mDevice->map_tile_y); };
1532 double GetMapScale()
const {
return GetVar(mDevice->
map_scale); };
1544 uint32_t GetPendingCount()
const {
return GetVar(mDevice->
pending_count); };
1547 uint32_t GetHypothCount()
const {
return GetVar(mDevice->
hypoth_count); };
1551 {
return GetVar(mDevice->hypoths[aIndex]); };
1561 void SetPose(
double pose[3],
double cov[6]);
1564 uint32_t GetNumHypoths()
const {
return GetVar(mDevice->
hypoth_count); };
1568 uint32_t GetNumParticles()
const {
return GetVar(mDevice->num_particles); };
1575 class PLAYERCC_EXPORT LogProxy :
public ClientProxy
1579 void Subscribe(uint32_t aIndex);
1587 LogProxy(PlayerClient *aPc, uint32_t aIndex=0);
1594 int GetType()
const {
return GetVar(mDevice->
type); };
1597 int GetState()
const {
return GetVar(mDevice->
state); };
1604 void SetState(
int aState);
1607 void SetWriteState(
int aState);
1610 void SetReadState(
int aState);
1616 void SetFilename(
const std::string aFilename);
1622 class PLAYERCC_EXPORT MapProxy :
public ClientProxy
1626 void Subscribe(uint32_t aIndex);
1634 MapProxy(PlayerClient *aPc, uint32_t aIndex=0);
1643 int GetCellIndex(
int x,
int y)
const
1644 {
return y*GetWidth() + x; };
1647 int8_t GetCell(
int x,
int y)
const
1648 {
return GetVar(mDevice->
cells[GetCellIndex(x,y)]); };
1651 double GetResolution()
const {
return GetVar(mDevice->
resolution); };
1655 uint32_t GetWidth()
const {
return GetVar(mDevice->
width); };
1658 uint32_t GetHeight()
const {
return GetVar(mDevice->height); };
1660 double GetOriginX()
const {
return GetVar(mDevice->
origin[0]); };
1661 double GetOriginY()
const {
return GetVar(mDevice->
origin[1]); };
1664 int8_t GetDataRange()
const {
return GetVar(mDevice->
data_range); };
1667 void GetMap(int8_t* aMap)
const
1669 return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->
cells),
1670 reinterpret_cast<int8_t*>(mDevice->
cells+GetWidth()*GetHeight()),
1680 class PLAYERCC_EXPORT OpaqueProxy :
public ClientProxy
1685 void Subscribe(uint32_t aIndex);
1694 OpaqueProxy(PlayerClient *aPc, uint32_t aIndex=0);
1699 uint32_t GetCount()
const {
return GetVar(mDevice->
data_count); };
1702 void GetData(uint8_t* aDest)
const
1704 return GetVarByRef(mDevice->
data,
1720 class PLAYERCC_EXPORT PlannerProxy :
public ClientProxy
1725 void Subscribe(uint32_t aIndex);
1734 PlannerProxy(PlayerClient *aPc, uint32_t aIndex=0);
1739 void SetGoalPose(
double aGx,
double aGy,
double aGa);
1742 void SetStartPose(
double aSx,
double aSy,
double aSa);
1746 void RequestWaypoints();
1750 void SetEnable(
bool aEnable);
1753 uint32_t GetPathValid()
const {
return GetVar(mDevice->
path_valid); };
1756 uint32_t GetPathDone()
const {
return GetVar(mDevice->
path_done); };
1764 double GetPx()
const {
return GetVar(mDevice->
px); };
1767 double GetPy()
const {
return GetVar(mDevice->py); };
1770 double GetPa()
const {
return GetVar(mDevice->pa); };
1785 double GetGx()
const {
return GetVar(mDevice->
gx); };
1788 double GetGy()
const {
return GetVar(mDevice->gy); };
1791 double GetGa()
const {
return GetVar(mDevice->ga); };
1806 double GetWx()
const {
return GetVar(mDevice->
wx); };
1809 double GetWy()
const {
return GetVar(mDevice->wy); };
1812 double GetWa()
const {
return GetVar(mDevice->wa); };
1827 double GetIx(
int i)
const;
1830 double GetIy(
int i)
const;
1833 double GetIa(
int i)
const;
1838 assert(aIndex < GetWaypointCount());
1850 int GetCurrentWaypointId()
const
1854 uint32_t GetWaypointCount()
const
1862 {
return GetWaypoint(aIndex); }
1869 class PLAYERCC_EXPORT Pointcloud3dProxy :
public ClientProxy
1873 void Subscribe(uint32_t aIndex);
1881 Pointcloud3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1884 ~Pointcloud3dProxy();
1887 uint32_t GetCount()
const {
return GetVar(mDevice->
points_count); };
1891 {
return GetVar(mDevice->
points[aIndex]); };
1904 class PLAYERCC_EXPORT Position1dProxy :
public ClientProxy
1909 void Subscribe(uint32_t aIndex);
1918 Position1dProxy(PlayerClient *aPc, uint32_t aIndex=0);
1925 void SetSpeed(
double aVel);
1930 void GoTo(
double aPos,
double aVel);
1952 b.
sl = mDevice->size[0];
1953 b.
sw = mDevice->size[1];
1961 void SetMotorEnable(
bool enable);
1965 void SetOdometry(
double aPos);
1968 void ResetOdometry() { SetOdometry(0); };
1981 double GetPos()
const {
return GetVar(mDevice->
pos); };
1984 double GetVel()
const {
return GetVar(mDevice->
vel); };
1987 bool GetStall()
const {
return GetVar(mDevice->
stall) != 0 ? true :
false; };
1990 uint8_t GetStatus()
const {
return GetVar(mDevice->
status); };
1993 bool IsLimitMin()
const
1994 {
return (GetVar(mDevice->
status) &
1998 bool IsLimitCen()
const
1999 {
return (GetVar(mDevice->
status) &
2003 bool IsLimitMax()
const
2004 {
return (GetVar(mDevice->
status) &
2008 bool IsOverCurrent()
const
2009 {
return (GetVar(mDevice->
status) &
2013 bool IsTrajComplete()
const
2014 {
return (GetVar(mDevice->
status) &
2018 bool IsEnabled()
const
2019 {
return (GetVar(mDevice->
status) &
2028 class PLAYERCC_EXPORT Position2dProxy :
public ClientProxy
2033 void Subscribe(uint32_t aIndex);
2042 Position2dProxy(PlayerClient *aPc, uint32_t aIndex=0);
2049 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aYawSpeed);
2053 void SetSpeed(
double aXSpeed,
double aYawSpeed)
2054 {
return SetSpeed(aXSpeed, 0, aYawSpeed);}
2058 {
return SetSpeed(vel.
px, vel.
py, vel.
pa);}
2063 void SetVelHead(
double aXSpeed,
double aYSpeed,
double aYawHead);
2067 void SetVelHead(
double aXSpeed,
double aYawHead)
2068 {
return SetVelHead(aXSpeed, 0, aYawHead);}
2082 void GoTo(
double aX,
double aY,
double aYaw)
2086 void SetCarlike(
double aXSpeed,
double aDriveAngle);
2097 scoped_lock_t lock(mPc->mMutex);
2109 b.
sl = mDevice->size[0];
2110 b.
sw = mDevice->size[1];
2118 void SetMotorEnable(
bool enable);
2131 void ResetOdometry();
2139 void SetOdometry(
double aX,
double aY,
double aYaw);
2167 double GetXPos()
const {
return GetVar(mDevice->
px); };
2170 double GetYPos()
const {
return GetVar(mDevice->py); };
2173 double GetYaw()
const {
return GetVar(mDevice->pa); };
2176 double GetXSpeed()
const {
return GetVar(mDevice->
vx); };
2179 double GetYSpeed()
const {
return GetVar(mDevice->vy); };
2182 double GetYawSpeed()
const {
return GetVar(mDevice->va); };
2185 bool GetStall()
const {
return GetVar(mDevice->
stall) != 0 ? true :
false; };
2195 class PLAYERCC_EXPORT Position3dProxy :
public ClientProxy
2200 void Subscribe(uint32_t aIndex);
2209 Position3dProxy(PlayerClient *aPc, uint32_t aIndex=0);
2216 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aZSpeed,
2217 double aRollSpeed,
double aPitchSpeed,
double aYawSpeed);
2222 void SetSpeed(
double aXSpeed,
double aYSpeed,
2223 double aZSpeed,
double aYawSpeed)
2224 { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
2227 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aYawSpeed)
2228 { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
2232 void SetSpeed(
double aXSpeed,
double aYawSpeed)
2233 { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
2251 void GoTo(
double aX,
double aY,
double aZ,
2252 double aRoll,
double aPitch,
double aYaw)
2262 void SetMotorEnable(
bool aEnable);
2266 void SelectVelocityControl(
int aMode);
2269 void ResetOdometry();
2274 void SetOdometry(
double aX,
double aY,
double aZ,
2275 double aRoll,
double aPitch,
double aYaw);
2296 double GetXPos()
const {
return GetVar(mDevice->
pos_x); };
2299 double GetYPos()
const {
return GetVar(mDevice->pos_y); };
2302 double GetZPos()
const {
return GetVar(mDevice->pos_z); };
2305 double GetRoll()
const {
return GetVar(mDevice->
pos_roll); };
2308 double GetPitch()
const {
return GetVar(mDevice->pos_pitch); };
2311 double GetYaw()
const {
return GetVar(mDevice->pos_yaw); };
2314 double GetXSpeed()
const {
return GetVar(mDevice->
vel_x); };
2317 double GetYSpeed()
const {
return GetVar(mDevice->vel_y); };
2320 double GetZSpeed()
const {
return GetVar(mDevice->vel_z); };
2323 double GetRollSpeed()
const {
return GetVar(mDevice->
vel_roll); };
2326 double GetPitchSpeed()
const {
return GetVar(mDevice->vel_pitch); };
2329 double GetYawSpeed()
const {
return GetVar(mDevice->vel_yaw); };
2332 bool GetStall ()
const {
return GetVar(mDevice->
stall) != 0 ? true :
false; };
2336 class PLAYERCC_EXPORT PowerProxy :
public ClientProxy
2340 void Subscribe(uint32_t aIndex);
2348 PowerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2353 double GetCharge()
const {
return GetVar(mDevice->
charge); };
2356 double GetPercent()
const {
return GetVar(mDevice->
percent); };
2359 double GetJoules()
const {
return GetVar(mDevice->
joules); };
2362 double GetWatts()
const {
return GetVar(mDevice->
watts); };
2365 bool GetCharging()
const {
return GetVar(mDevice->
charging) != 0 ? true :
false;};
2368 bool IsValid()
const {
return GetVar(mDevice->
valid) != 0 ? true :
false;};
2377 class PLAYERCC_EXPORT PtzProxy :
public ClientProxy
2382 void Subscribe(uint32_t aIndex);
2390 PtzProxy(PlayerClient *aPc, uint32_t aIndex=0);
2399 void SetCam(
double aPan,
double aTilt,
double aZoom);
2402 void SetSpeed(
double aPanSpeed=0,
double aTiltSpeed=0,
double aZoomSpeed=0);
2406 void SelectControlMode(uint32_t aMode);
2409 double GetPan()
const {
return GetVar(mDevice->
pan); };
2411 double GetTilt()
const {
return GetVar(mDevice->tilt); };
2413 double GetZoom()
const {
return GetVar(mDevice->
zoom); };
2423 class PLAYERCC_EXPORT RangerProxy :
public ClientProxy
2427 void Subscribe(uint32_t aIndex);
2435 RangerProxy(PlayerClient *aPc, uint32_t aIndex=0);
2440 uint32_t GetElementCount()
const {
return GetVar(mDevice->
element_count); };
2445 player_bbox3d_t GetDeviceSize()
const {
return GetVar(mDevice->device_size); };
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); }
2460 uint32_t GetPointCount()
const {
return GetVar(mDevice->
points_count); };
2465 uint32_t GetIntensityCount()
const {
return GetVar(mDevice->
intensities_count); } ;
2467 double GetIntensity(uint32_t aIndex)
const;
2471 void SetPower(
bool aEnable);
2475 void SetIntensityData(
bool aEnable);
2484 void Configure(
double aMinAngle,
2494 void RequestConfigure();
2497 double GetMinAngle()
const {
return GetVar(mDevice->
min_angle); };
2500 double GetMaxAngle()
const {
return GetVar(mDevice->
max_angle); };
2503 double GetAngularRes()
const {
return GetVar(mDevice->
angular_res); };
2506 double GetMinRange()
const {
return GetVar(mDevice->
min_range); };
2509 double GetMaxRange()
const {
return GetVar(mDevice->
max_range); };
2512 double GetRangeRes()
const {
return GetVar(mDevice->
range_res); };
2515 double GetFrequency()
const {
return GetVar(mDevice->
frequency); };
2520 class PLAYERCC_EXPORT RFIDProxy :
public ClientProxy
2525 void Subscribe(uint32_t aIndex);
2533 RFIDProxy(PlayerClient *aPc, uint32_t aIndex=0);
2538 uint32_t GetTagsCount()
const {
return GetVar(mDevice->
tags_count); };
2541 {
return GetVar(mDevice->
tags[aIndex]);};
2548 {
return(GetRFIDTag(aIndex)); }
2555 class PLAYERCC_EXPORT SimulationProxy :
public ClientProxy
2559 void Subscribe(uint32_t aIndex);
2567 SimulationProxy(PlayerClient *aPc, uint32_t aIndex=0);
2573 void SetPose2d(
char* identifier,
double x,
double y,
double a);
2577 void GetPose2d(
char* identifier,
double& x,
double& y,
double& a);
2581 void SetPose3d(
char* identifier,
double x,
double y,
double z,
2582 double roll,
double pitch,
double yaw);
2586 void GetPose3d(
char* identifier,
double& x,
double& y,
double& z,
2587 double& roll,
double& pitch,
double& yaw,
double& time);
2590 void GetProperty(
char* identifier,
char *name,
void *value,
size_t value_len );
2593 void SetProperty(
char* identifier,
char *name,
void *value,
size_t value_len );
2602 class PLAYERCC_EXPORT SonarProxy :
public ClientProxy
2606 void Subscribe(uint32_t aIndex);
2614 SonarProxy(PlayerClient *aPc, uint32_t aIndex=0);
2619 uint32_t GetCount()
const {
return GetVar(mDevice->
scan_count); };
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); }
2629 uint32_t GetPoseCount()
const {
return GetVar(mDevice->
pose_count); };
2633 {
return GetVar(mDevice->
poses[aIndex]); };
2650 class PLAYERCC_EXPORT SpeechProxy :
public ClientProxy
2655 void Subscribe(uint32_t aIndex);
2663 SpeechProxy(PlayerClient *aPc, uint32_t aIndex=0);
2669 void Say(std::string aStr);
2675 class PLAYERCC_EXPORT SpeechRecognitionProxy :
public ClientProxy
2677 void Subscribe(uint32_t aIndex);
2688 std::string GetWord(uint32_t aWord)
const{
2690 return std::string(mDevice->words[aWord]);
2694 uint32_t GetCount(
void)
const {
return GetVar(mDevice->wordCount); }
2698 std::string operator [](uint32_t aWord) {
return(GetWord(aWord)); }
2704 class PLAYERCC_EXPORT StereoProxy :
public ClientProxy
2707 void Subscribe(uint32_t aIndex);
2714 void SaveFrame(
const std::string aPrefix, uint32_t aWidth,
playerc_camera_t aDevice, uint8_t aIndex);
2720 std::string mPrefix;
2723 uint32_t mFrameNo[3];
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); };
2746 void DecompressLeft(){
return Decompress(mDevice->left_channel); };
2748 void DecompressRight(){
return Decompress(mDevice->right_channel); };
2750 void DecompressDisparity(){
return Decompress(mDevice->disparity); };
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); };
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); };
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); };
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); };
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); };
2806 void GetLeftImage(uint8_t* aImage)
const
2808 return GetVarByRef(mDevice->left_channel.
image,
2816 void GetRightImage(uint8_t* aImage)
const
2818 return GetVarByRef(mDevice->right_channel.
image,
2826 void GetDisparityImage(uint8_t* aImage)
const
2828 return GetVarByRef(mDevice->disparity.
image,
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); };
2850 uint32_t GetCount()
const {
return GetVar(mDevice->points_count); };
2854 {
return GetVar(mDevice->points[aIndex]); };
2865 class PLAYERCC_EXPORT VectorMapProxy :
public ClientProxy
2871 void Subscribe(uint32_t aIndex);
2878 bool map_info_cached;
2881 VectorMapProxy(PlayerClient *aPc, uint32_t aIndex=0);
2889 void GetLayerData(
unsigned layer_index);
2892 int GetLayerCount()
const;
2895 std::vector<std::string> GetLayerNames()
const;
2898 int GetFeatureCount(
unsigned layer_index)
const;
2901 const uint8_t * GetFeatureData(
unsigned layer_index,
unsigned feature_index)
const;
2904 size_t GetFeatureDataCount(
unsigned layer_index,
unsigned feature_index)
const;
2909 class PLAYERCC_EXPORT WiFiProxy:
public ClientProxy
2914 void Subscribe(uint32_t aIndex);
2922 WiFiProxy(PlayerClient *aPc, uint32_t aIndex=0);
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; } ;
2956 class PLAYERCC_EXPORT WSNProxy :
public ClientProxy
2961 void Subscribe(uint32_t aIndex);
2969 WSNProxy(PlayerClient *aPc, uint32_t aIndex=0);
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); };
2982 GetNodeDataPacket()
const {
return GetVar(mDevice->
data_packet); };
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);
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);
3010 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::AioProxy& c);
3016 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::DioProxy& c);
3018 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::GpsProxy& 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);
3023 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::LimbProxy& 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);
3034 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::PtzProxy& 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);
Note: the structure describing the Cooperating Object's data packet is declared in Player.
Definition: playerc.h:1529
Position3d device data.
Definition: playerc.h:2978
player_bbox2d_t fiducial_size
Dimensions of the fiducials in units of (m).
Definition: player_interfaces.h:1721
player_coopobject_sensor_t * alarm_data
Active alarms array.
Definition: playerc.h:1571
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition: playerc.h:1402
Power device data.
Definition: playerc.h:3082
The PlannerProxy proxy provides an interface to a 2D motion planner.
Definition: playerc++.h:1718
int status
Status bitfield of extra data in the following order:
Definition: playerc.h:2820
Structure describing a single RFID tag.
Definition: playerc.h:3630
Fiducial finder data.
Definition: playerc.h:1685
int32_t default_input
default input channel (-1 for none)
Definition: player_interfaces.h:1578
IMU proxy state data.
Definition: playerc.h:3767
#define PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE
Status byte: limit trajectory complete.
Definition: player_interfaces.h:3534
uint32_t alarm_data_count
Number of alarms included.
Definition: playerc.h:1569
The ImuProxy class is used to control an imu device.
Definition: playerc++.h:1115
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition: playerc.h:1943
uint32_t channels_count
number of channels in list
Definition: player_interfaces.h:1533
player_coopobject_sensor_t * sensor_data
Sensor measurements array.
Definition: playerc.h:1567
int mode
Mode (master, ad-hoc, etc).
Definition: playerc.h:3422
double wx
Current waypoint location (m, m, radians)
Definition: playerc.h:2720
The CoopObjectProxy class is used to control a coopobject device.
Definition: playerc++.h:596
The Position2dProxy class is used to control a position2d device.
Definition: playerc++.h:2026
double resolution
Map resolution, m/cell.
Definition: playerc.h:2538
double proll
roll [rad]
Definition: player.h:236
double utm_e
UTM easting and northing (meters).
Definition: playerc.h:1763
Structure describing the WSN node's data packet.
Definition: player_interfaces.h:4386
uint32_t element_count
Number of individual elements in the device.
Definition: playerc.h:3227
double sw
Width [m].
Definition: player.h:247
double max_range
Maximum range of sensor, in m.
Definition: playerc.h:2180
Vectormap proxy.
Definition: playerc.h:2592
The SimulationProxy proxy provides access to a simulation device.
Definition: playerc++.h:2553
Graphics3d device data.
Definition: playerc.h:1876
uint8_t capacity
The capacity of the gripper's store - if 0, the gripper cannot store.
Definition: playerc.h:1949
Data: state (PLAYER_LIMB_DATA_STATE)
Definition: player_interfaces.h:4072
int pose_count
Number of pose values.
Definition: playerc.h:1391
A rectangular bounding box, used to define the size of an object.
Definition: player.h:253
int path_done
Have we arrived at the goal?
Definition: playerc.h:2711
Audio device data.
Definition: playerc.h:1127
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition: playerc.h:3691
Actarray device data.
Definition: playerc.h:1033
uint32_t node_type
The type of WSN node.
Definition: playerc.h:3827
double speed
Speed over ground, in m/s.
Definition: playerc.h:1756
uint32_t node_id
The ID of the WSN node.
Definition: playerc.h:3829
double px
X [m].
Definition: player.h:230
double py
Y [m].
Definition: player.h:188
int intensity_on
Is intesity data returned.
Definition: playerc.h:2165
uint32_t data_count
length of raw data
Definition: player_interfaces.h:1466
A pose in the plane.
Definition: player.h:216
uint32_t actuators_count
The number of actuators in the array.
Definition: playerc.h:1039
uint8_t num_beams
The number of breakbeams the gripper has.
Definition: playerc.h:1947
double y1
Endpoints [m].
Definition: player.h:299
uint32_t poses_count
the number of ir samples returned by this robot
Definition: player_interfaces.h:2133
double range_res
Range resolution [m].
Definition: playerc.h:3241
double pos_x
Device position (m).
Definition: playerc.h:2990
An angle in 3D space.
Definition: player.h:205
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc.h:2725
double px
X [m].
Definition: player.h:186
int scan_count
Number of points in the scan.
Definition: playerc.h:3368
Blobfinder device data.
Definition: playerc.h:1342
player_pose3d_t * poses
Pose of each sonar relative to robot (m, m, radians).
Definition: playerc.h:3365
Wifi device proxy.
Definition: playerc.h:3437
double pz
Z [m].
Definition: player.h:234
uint32_t user_data_count
User defined message size (in bytes)
Definition: playerc.h:1574
player_audio_seq_item_t * tones
the tones
Definition: player_interfaces.h:1504
The WSNProxy class is used to control a wsn device.
Definition: playerc++.h:2954
The LogProxy proxy provides access to a log device.
Definition: playerc++.h:1573
int laser_id
Laser IDentification information.
Definition: playerc.h:2203
The BumperProxy class is used to read from a bumper device.
Definition: playerc++.h:474
double x1
Endpoints [m].
Definition: player.h:297
A color descriptor.
Definition: player.h:319
player_audio_mixer_channel_detail_t * details
the tones
Definition: player_interfaces.h:1574
double freq
Frequency (MHz).
Definition: playerc.h:3428
GPS proxy data.
Definition: playerc.h:1738
Definition: playerclient.h:94
double vdop
Vertical dilution of precision.
Definition: playerc.h:1769
the Stereo proxy provides access to the stereo device.
Definition: playerc++.h:2702
Limb device data.
Definition: playerc.h:2322
double px
X [m].
Definition: player.h:219
double range_res
Range resolution, in m.
Definition: playerc.h:2177
A line segment, used to construct vector-based maps.
Definition: player.h:290
The SpeechProxy class is used to control a speech device.
Definition: playerc++.h:2648
double x1
Endpoints [m].
Definition: player.h:313
double robot_pose[3]
Robot pose (m,m,rad), filled in if the scan came with a pose attached.
Definition: playerc.h:2162
uint32_t intensities_count
Number of intensities in a scan.
Definition: playerc.h:3262
int pose_count
Number of pose values.
Definition: playerc.h:3361
int valid
status bits.
Definition: playerc.h:3089
#define PLAYER_POSITION1D_STATUS_LIMIT_CEN
Status byte: limit center.
Definition: player_interfaces.h:3528
#define PLAYER_POSITION1D_STATUS_LIMIT_MAX
Status byte: limit max.
Definition: player_interfaces.h:3530
Player mixer channels.
Definition: player_interfaces.h:1530
uint32_t node_parent_id
The ID of the WSN node's parent (if existing).
Definition: playerc.h:3831
double pyaw
yaw [rad]
Definition: player.h:240
A point in 3D space.
Definition: player.h:193
int waypoint_count
Number of waypoints in the plan.
Definition: playerc.h:2728
uint32_t ranges_count
Number of ranges in a scan.
Definition: playerc.h:3257
uint8_t * image
Image data (byte aligned, row major order).
Definition: playerc.h:1471
double vel
Odometric velocity [m/s] or [rad/s].
Definition: playerc.h:2804
player_fiducial_geom_t fiducial_geom
Geometry in robot cs.
Definition: playerc.h:1694
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition: playerc.h:3778
Gripper device data.
Definition: playerc.h:1932
uint8_t request
Request type.
Definition: playerc.h:1581
int8_t data_range
Value for each cell (-range <= EMPTY < 0, unknown = 0, 0 < OCCUPIED <= range)
Definition: playerc.h:2547
char drivername[PLAYER_MAX_DRIVER_STRING_LEN]
The driver name.
Definition: playerc.h:498
Structure containing a single actuator's information.
Definition: player_interfaces.h:3793
int32_t default_output
default output channel (-1 for none)
Definition: player_interfaces.h:1576
double min_angle
Start angle of scans [rad].
Definition: playerc.h:3230
player_audio_wav_t wav_data
last block of recorded data
Definition: playerc.h:1136
double map_scale
Map scale (m/cell).
Definition: playerc.h:2413
uint8_t origin
The type of Cooperating Object.
Definition: playerc.h:1542
uint32_t tones_count
number of tones in list
Definition: player_interfaces.h:1502
player_pose3d_t * poses
the pose of each IR detector on this robot
Definition: player_interfaces.h:2135
double py
Y [m].
Definition: player.h:221
Player audio sequence.
Definition: player_interfaces.h:1499
The PowerProxy class controls a power device.
Definition: playerc++.h:2334
uint16_t id
Cooperating Object ID.
Definition: playerc.h:1544
uint8_t state
The gripper's state: may be one of PLAYER_GRIPPER_STATE_OPEN, PLAYER_GRIPPER_STATE_CLOSED,...
Definition: playerc.h:1954
Hypothesis format.
Definition: player_interfaces.h:2335
int stall
Stall flag [0, 1].
Definition: playerc.h:2901
player_wsn_node_data_t data_packet
The WSN node's data packet.
Definition: playerc.h:3833
player_bumper_define_t * poses
Pose of each bumper relative to robot (mm, mm, deg, mm, mm).
Definition: playerc.h:1396
unsigned int blobs_count
A list of detected blobs.
Definition: playerc.h:1351
double pos
Odometric pose [m] or [rad].
Definition: playerc.h:2801
float * ranges
ranges [m]
Definition: player_interfaces.h:2124
double x0
Endpoints [m].
Definition: player.h:293
Camera proxy data.
Definition: playerc.h:1442
int state
Is logging/playback enabled? Call playerc_log_get_state() to fill it.
Definition: playerc.h:2483
Bumper proxy data.
Definition: playerc.h:1385
double err_horz
Horizontal and vertical error (meters).
Definition: playerc.h:1772
double course
Course made good (heading if the robot moves along its longitudinal axis), in radians.
Definition: playerc.h:1760
#define PLAYER_POSITION1D_STATUS_LIMIT_MIN
Status byte: limit min.
Definition: player_interfaces.h:3526
int data_count
Size of data (bytes)
Definition: playerc.h:2659
uint8_t command
Command type.
Definition: playerc.h:1579
The LaserProxy class is used to control a laser device.
Definition: playerc++.h:1222
player_point_2d_t * point
Scan data; x, y position (m).
Definition: playerc.h:2192
stereo proxy data.
Definition: playerc.h:3722
Position1d device data.
Definition: playerc.h:2789
double watts
power currently being used (Watts).
Definition: playerc.h:3102
The AioProxy class is used to read from a aio (analog I/O) device.
Definition: playerc++.h:207
The RangerProxy class is used to control a ranger device.
Definition: playerc++.h:2421
int hypoth_count
List of possible poses.
Definition: playerc.h:2428
player_pose3d_t pose
The complete pose of the IMU in 3D coordinates + angles
Definition: playerc.h:3773
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition: playerc.h:1142
The SpeechRecognition proxy provides access to a speech_recognition device.
Definition: playerc++.h:2673
uint32_t state
current driver state
Definition: playerc.h:1145
double ppitch
pitch [rad]
Definition: player.h:238
Laser proxy data.
Definition: playerc.h:2150
The WiFiProxy class controls a wifi device.
Definition: playerc++.h:2907
playerc_wifi_link_t * links
A list containing info for each link.
Definition: playerc.h:3443
PTZ device data.
Definition: playerc.h:3139
double sh
Height [m].
Definition: player.h:260
Ranger proxy data.
Definition: playerc.h:3221
The DioProxy class is used to read from a dio (digital I/O) device.
Definition: playerc++.h:763
The SonarProxy class is used to control a sonar device.
Definition: playerc++.h:2600
A rectangular bounding box, used to define the origin and bounds of an object.
Definition: player.h:306
player_audio_seq_t seq_data
last block of seq data
Definition: playerc.h:1139
int path_valid
Did the planner find a valid path?
Definition: playerc.h:2708
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition: playerc.h:3688
player_audio_mixer_channel_list_detail_t channel_details_list
Details of the channels from the mixer.
Definition: playerc.h:1133
double x0
Origin x [m].
Definition: player.h:309
double pose[3]
Robot geometry in robot cs: pose gives the position1d and orientation, size gives the extent.
Definition: playerc.h:2797
The client proxy base class.
Definition: clientproxy.h:77
Player mixer channel.
Definition: player_interfaces.h:1513
int scan_count
Number of points in the scan.
Definition: playerc.h:2168
Note: the structure describing the WSN node's data packet is declared in Player.
Definition: playerc.h:3821
double sl
Length [m].
Definition: player.h:258
double * scan
Scan data: range (m).
Definition: playerc.h:3371
double waypoint_distance
Straight-line distance along allwaypoints in the current plan.
Definition: playerc.h:2736
The Position1dProxy class is used to control a position1d device.
Definition: playerc++.h:1902
int bpp
Image bits-per-pixel (8, 16, 24).
Definition: playerc.h:1451
Info on a single detected fiducial.
Definition: player_interfaces.h:1685
char * cells
Occupancy for each cell.
Definition: playerc.h:2550
A rectangular bounding box, used to define the size of an object.
Definition: player.h:244
uint32_t parameters_count
Request/command parameters array size (in bytes)
Definition: playerc.h:1583
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:2213
The RFIDProxy class is used to control a rfid device.
Definition: playerc++.h:2518
player_orientation_3d_t base_orientation
The orientation of the base of the actarray.
Definition: playerc.h:1050
Speech proxy data.
Definition: playerc.h:3556
double px
Current pose (m, m, radians).
Definition: playerc.h:2714
The CameraProxy class can be used to get images from a camera device.
Definition: playerc++.h:524
#define PLAYER_POSITION1D_STATUS_ENABLED
Status byte: enabled.
Definition: player_interfaces.h:3536
RFID proxy data.
Definition: playerc.h:3641
Note: the structure describing the HEALTH's data packet is declared in Player.
Definition: playerc.h:2015
The GpsProxy class is used to control a gps device.
Definition: playerc++.h:852
Position2d device data.
Definition: playerc.h:2883
double pos_roll
Device orientation (radians).
Definition: playerc.h:2993
uint8_t mac[32]
Mac accress.
Definition: playerc.h:3413
player_bbox3d_t size
Size of the detector.
Definition: player_interfaces.h:1719
uint16_t tags_count
The number of RFID tags found.
Definition: playerc.h:3647
int map_tile_x
Next map tile to read.
Definition: playerc.h:2416
joystick proxy data.
Definition: playerc.h:2105
double sw
Width [m].
Definition: player.h:256
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
Opaque device data.
Definition: playerc.h:2653
The GripperProxy class is used to control a gripper device.
Definition: playerc++.h:1002
double py
Y [m].
Definition: player.h:232
playerc_rfidtag_t * tags
The list of RFID tags.
Definition: playerc.h:3650
int * intensity
Scan reflection intensity values (0-3).
Definition: playerc.h:2197
double scan_res
Angular resolution in radians.
Definition: playerc.h:2174
int encrypt
Encrypted?
Definition: playerc.h:3425
The ActArrayProxy class is used to control a actarray device.
Definition: playerc++.h:139
uint8_t * user_data
User defined data array.
Definition: playerc.h:1576
uint16_t parent_id
Cooperating Object Parent ID (if existing)
Definition: playerc.h:1546
Simulation device proxy.
Definition: playerc.h:3480
enum player_graphics3d_draw_mode player_graphics3d_draw_mode_t
Drawmode: enumeration that defines the drawing mode.
double max_range
Maximum range [m].
Definition: playerc.h:3239
double y0
Origin y [m].
Definition: player.h:311
The BlinkenlightProxy class is used to enable and disable a flashing indicator light,...
Definition: playerc++.h:423
Player mixer channel detail.
Definition: player_interfaces.h:1552
Graphics2d device data.
Definition: playerc.h:1809
double alt
Altitude (meters).
Definition: playerc.h:1753
double pose[3]
Laser geometry in the robot cs: pose gives the position and orientation, size gives the extent.
Definition: playerc.h:2158
int qual
Link properties.
Definition: playerc.h:3431
double frequency
Scanning frequency [Hz].
Definition: playerc.h:3243
Map proxy data.
Definition: playerc.h:2532
int stall
Stall flag [0, 1].
Definition: playerc.h:3002
double angular_res
Scan resolution [rad].
Definition: playerc.h:3234
#define PLAYER_POSITION1D_STATUS_OC
Status byte: limit over current.
Definition: player_interfaces.h:3532
int pending_count
The number of pending (unprocessed) sensor readings.
Definition: playerc.h:2422
uint8_t stored
The number of currently-stored objects.
Definition: playerc.h:1958
double(* scan)[2]
Scan data; range (m) and bearing (radians).
Definition: playerc.h:2189
A pose in space.
Definition: player.h:227
uint8_t ip[32]
IP address.
Definition: playerc.h:3416
int compression
Image compression method.
Definition: playerc.h:1462
The PlayerClient is used for communicating with the player server.
Definition: playerclient.h:119
int sat_count
Number of satellites in view.
Definition: playerc.h:1778
double gx
Goal location (m, m, radians)
Definition: playerc.h:2717
player_audio_mixer_channel_t * channels
the channels
Definition: player_interfaces.h:1535
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam,...
Definition: playerc.h:2208
double max_angle
End angle of scans [rad].
Definition: playerc.h:3232
pointcloud3d proxy data.
Definition: playerc.h:3682
double y0
Endpoints [m].
Definition: player.h:295
uint8_t * parameters
Request/command parameters array
Definition: playerc.h:1585
A point in the plane.
Definition: player.h:183
int quality
Quality of fix 0 = invalid, 1 = GPS fix, 2 = DGPS fix.
Definition: playerc.h:1775
uint32_t beams
The position of the object in the gripper.
Definition: playerc.h:1956
uint32_t ranges_count
number of samples
Definition: player_interfaces.h:2122
int bumper_count
Number of points in the scan.
Definition: playerc.h:1399
double scan_start
Start bearing of the scan (radians).
Definition: playerc.h:2171
int fiducials_count
List of detected beacons.
Definition: playerc.h:1697
The OpaqueProxy proxy provides an interface to a generic opaque.
Definition: playerc++.h:1678
player_devaddr_t addr
Player id of the device.
Definition: playerc.h:495
uint8_t essid[32]
ESSID id.
Definition: playerc.h:3419
The LocalizeProxy class is used to control a localize device, which can provide multiple pose hypothe...
Definition: playerc++.h:1499
The VectorMapProxy class is used to interface to a vectormap.
Definition: playerc++.h:2863
int charging
charging flag.
Definition: playerc.h:3105
Player audio sequence item.
Definition: player_interfaces.h:1481
The map proxy provides access to a map device.
Definition: playerc++.h:1620
Actuator geometry.
Definition: player_interfaces.h:3821
double percent
Battery charge (percent full).
Definition: playerc.h:3095
double sl
Length [m].
Definition: player.h:249
double min_range
Minimum range [m].
Definition: playerc.h:3237
double scanning_frequency
Scanning frequency in Hz.
Definition: playerc.h:2183
Info about an available (but not necessarily subscribed) device.
Definition: playerc.h:492
double charge
Battery charge (Volts).
Definition: playerc.h:3092
int stall
Stall flag [0, 1].
Definition: playerc.h:2807
double zoom
The current zoom value (field of view angle).
Definition: playerc.h:3150
uint8_t type
The type of sensor (see above)
Definition: player_interfaces.h:5476
The Position3dProxy class is used to control a interface_position3d device.
Definition: playerc++.h:2193
Individual link info.
Definition: playerc.h:3410
Log proxy data.
Definition: playerc.h:2472
double(* waypoints)[3]
List of waypoints in the current plan (m,m,radians).
Definition: playerc.h:2732
unsigned int width
Image dimensions (pixels).
Definition: playerc.h:1348
3D Pointcloud element structure An element as stored in a 3D pointcloud, containing a 3D position plu...
Definition: player_interfaces.h:4861
data
Definition: player_interfaces.h:3449
double y1
Endpoints [m].
Definition: player.h:315
int16_t value
Value of the sensor/alarm
Definition: player_interfaces.h:5478
Dio proxy data.
Definition: playerc.h:1636
Sonar proxy data.
Definition: playerc.h:3355
double pa
yaw [rad]
Definition: player.h:223
int width
Image dimensions (pixels).
Definition: playerc.h:1448
Structure describing a single blob.
Definition: player_interfaces.h:1068
int map_size_x
Map dimensions (cells).
Definition: playerc.h:2410
Ir proxy data.
Definition: playerc.h:2056
Vectormap feature data.
Definition: player.h:264
double lat
Latitude and logitude (degrees).
Definition: playerc.h:1749
Data: calibrated IMU data (PLAYER_IMU_DATA_CALIB)
Definition: player_interfaces.h:4724
double vel_x
Linear velocity (m/s).
Definition: playerc.h:2996
player_pose3d_t device_pose
Device geometry in the robot CS: pose gives the position and orientation, size gives the extent.
Definition: playerc.h:3248
The AudioProxy class controls an audio device.
Definition: playerc++.h:247
Definition: player_interfaces.h:5284
The FiducialProxy class is used to control fiducial devices.
Definition: playerc++.h:804
int format
Image format (e.g., RGB888).
Definition: playerc.h:1454
player_pose3d_t pose
Pose of the detector in the robot cs.
Definition: player_interfaces.h:1717
int image_count
Size of image data (bytes)
Definition: playerc.h:1465
double joules
energy stored (Joules)
Definition: playerc.h:3098
Localization device data.
Definition: playerc.h:2404
uint8_t * data
raw data
Definition: player_interfaces.h:1468
Aio proxy data.
Definition: playerc.h:976
double px
Odometric pose (m, m, rad).
Definition: playerc.h:2895
int messageType
Flag to indicate that new info has come.
Definition: playerc.h:1535
Speech recognition proxy data.
Definition: playerc.h:3592
double pan
The current ptz pan and tilt angles.
Definition: playerc.h:3147
double utc_time
UTC time (seconds since the epoch)
Definition: playerc.h:1744
Planner device data.
Definition: playerc.h:2702
float x
Cooperating Object Position.
Definition: playerc.h:1558
uint32_t sensor_data_count
Number of sensors included.
Definition: playerc.h:1565
The IrProxy class is used to control an ir device.
Definition: playerc++.h:1173
uint8_t * data
Data
Definition: playerc.h:2662
double vel_roll
Angular velocity (radians/sec).
Definition: playerc.h:2999
double pose[3]
Robot geometry in robot cs: pose gives the position2d and orientation, size gives the extent.
Definition: playerc.h:2891
uint16_t index
Which device of that interface.
Definition: player.h:154
double hdop
Horizontal dilution of precision.
Definition: playerc.h:1766
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition: playerc.h:2898
uint16_t interf
The interface provided by the device; must be one of PLAYER_*_CODE.
Definition: player.h:152
Request/reply: get geometry.
Definition: player_interfaces.h:4147
int width
Map size, in cells.
Definition: playerc.h:2541
The geometry of a single bumper.
Definition: player_interfaces.h:1931
double * ranges
Raw range data; range (m).
Definition: playerc.h:2186
float * voltages
voltages [V]
Definition: player_interfaces.h:2120
The PtzProxy class is used to control a ptz device.
Definition: playerc++.h:2375
player_point_3d_t base_pos
The position of the base of the actarray.
Definition: playerc.h:1048
The LinuxjoystickProxy class is used to control a joystick device.
Definition: playerc++.h:1449
double origin[2]
Map origin, in meters (i.e., the real-world coordinates of cell 0,0)
Definition: playerc.h:2544
BlackBoard proxy.
Definition: playerc.h:1225
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc.h:2479
uint32_t points_count
Number of scan points.
Definition: playerc.h:3275
uint16_t RSSIsender
Cooperating Object data packet.
Definition: playerc.h:1551
The LimbProxy class is used to control a limb device.
Definition: playerc++.h:1395
uint32_t details_count
number of tones in list
Definition: player_interfaces.h:1572