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
145 void Subscribe(uint32_t aIndex);
160 void RequestGeometry(
void);
163 void SetPowerConfig(
bool aVal);
165 void SetBrakesConfig(
bool aVal);
167 void SetSpeedConfig(uint32_t aJoint,
float aSpeed);
170 void MoveTo(uint32_t aJoint,
float aPos);
172 void MoveToMulti(std::vector<float> aPos);
174 void MoveAtSpeed(uint32_t aJoint,
float aSpeed);
176 void MoveAtSpeedMulti(std::vector<float> aSpeed);
178 void MoveHome(
int aJoint);
180 void SetActuatorCurrent(uint32_t aJoint,
float aCurrent);
182 void SetActuatorCurrentMulti(std::vector<float> aCurrent);
201 {
return(GetActuatorData(aJoint)); }
211 void Subscribe(uint32_t aIndex);
223 uint32_t
GetCount()
const {
return(GetVar(mDevice->voltages_count)); };
227 {
return(GetVar(mDevice->voltages[aIndex])); };
230 void SetVoltage(uint32_t aIndex,
double aVoltage);
236 double operator [](uint32_t aIndex)
const
237 {
return GetVoltage(aIndex); }
250 void Subscribe(uint32_t aIndex);
298 void PlayWav(uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
301 void SetWavStremRec(
bool aState);
304 void PlaySample(
int aIndex);
313 void SetMixerLevel(uint32_t index,
float amplitude, uint8_t active);
320 void LoadSample(
int aIndex, uint32_t aDataCount, uint8_t *aData, uint32_t aFormat);
324 void GetSample(
int aIndex);
327 void RecordSample(
int aIndex, uint32_t aLength);
331 void GetMixerLevels();
335 void GetMixerDetails();
349 void Subscribe(uint32_t aIndex);
363 void UnsubscribeFromKey(
const char *key,
const char* group =
"");
365 void SubscribeToGroup(
const char* key);
367 void UnsubscribeFromGroup(
const char* group);
423 void Subscribe(uint32_t aIndex);
439 {
return GetVar(mDevice->blobs[aIndex]);};
444 uint32_t
GetHeight()
const {
return GetVar(mDevice->height); };
451 {
return(GetBlob(aIndex)); }
475 void Subscribe(uint32_t aIndex);
486 uint32_t GetCount()
const {
return GetVar(mDevice->
bumper_count); };
490 {
return GetVar(mDevice->
bumpers[aIndex]); };
496 void RequestBumperConfig();
503 {
return GetVar(mDevice->
poses[aIndex]); };
509 bool operator [](uint32_t aIndex)
const
510 {
return IsBumped(aIndex) != 0 ?
true :
false; }
522 virtual void Subscribe(uint32_t aIndex);
523 virtual void Unsubscribe();
541 void SaveFrame(
const std::string aPrefix, uint32_t aWidth=4);
553 uint32_t
GetHeight()
const {
return GetVar(mDevice->height); };
572 return GetVarByRef(mDevice->
image,
594 void Subscribe(uint32_t aIndex);
607 uint32_t
GetCount()
const {
return GetVar(mDevice->count); };
610 uint32_t
GetDigin()
const {
return GetVar(mDevice->digin); };
613 bool GetInput(uint32_t aIndex)
const;
616 void SetOutput(uint32_t aCount, uint32_t aDigout);
622 uint32_t operator [](uint32_t aIndex)
const
623 {
return GetInput(aIndex); }
634 void Subscribe(uint32_t aIndex);
651 {
return GetVar(mDevice->fiducials[aIndex]);};
666 void RequestGeometry();
673 {
return GetFiducialItem(aIndex); }
684 void Subscribe(uint32_t aIndex);
699 double GetLongitude()
const {
return GetVar(mDevice->lon); };
718 double GetUtmNorthing()
const {
return GetVar(mDevice->utm_n); };
725 double GetErrVertical()
const {
return GetVar(mDevice->err_vert); };
741 void Subscribe(uint32_t aIndex);
758 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
787 void Subscribe(uint32_t aIndex);
804 void Color(uint8_t red, uint8_t green, uint8_t blue, uint8_t alpha);
823 void Subscribe(uint32_t aIndex);
838 void RequestGeometry(
void);
876 void Subscribe(uint32_t aIndex);
892 float GetSystemCPU();
898 int64_t GetMemTotal();
901 int64_t GetMemUsed();
904 int64_t GetMemFree();
907 int64_t GetSwapTotal();
910 int64_t GetSwapUsed();
913 int64_t GetSwapFree();
916 float GetPercMemUsed();
919 float GetPercSwapUsed();
922 float GetPercTotalUsed();
934 void Subscribe(uint32_t aIndex);
964 void SetDatatype(
int aDatatype);
967 void ResetOrientation(
int aValue);
982 void Subscribe(uint32_t aIndex);
999 {
return GetVar(mDevice->data.
ranges[aIndex]); };
1002 {
return GetVar(mDevice->data.
voltages[aIndex]); };
1007 {
return GetVar(mDevice->poses.
poses[aIndex]);};
1016 double operator [](uint32_t aIndex)
const
1017 {
return GetRange(aIndex); }
1030 void Subscribe(uint32_t aIndex);
1037 double min_angle, max_angle, scan_res, range_res, scanning_frequency;
1085 {
return GetVar(mDevice->
point[aIndex]); };
1090 {
return GetVar(mDevice->
ranges[aIndex]); };
1094 {
return GetVar(mDevice->
scan[aIndex][1]); };
1099 {
return GetVar(mDevice->
intensity[aIndex]); };
1103 {
return GetVar(mDevice->
laser_id); };
1114 void Configure(
double aMinAngle,
1119 double aScanningFrequency);
1123 void RequestConfigure();
1164 b.
sl = mDevice->size[0];
1165 b.
sw = mDevice->size[1];
1171 {
return GetVar(mDevice->
min_left); };
1179 {
return GetMinLeft(); }
1183 {
return GetMinRight(); }
1189 double operator [] (uint32_t index)
const
1190 {
return GetRange(index);}
1203 void Subscribe(uint32_t aIndex);
1216 void RequestGeometry(
void);
1219 void SetPowerConfig(
bool aVal);
1221 void SetBrakesConfig(
bool aVal);
1223 void SetSpeedConfig(
float aSpeed);
1226 void MoveHome(
void);
1230 void SetPose(
float aPX,
float aPY,
float aPZ,
1231 float aAX,
float aAY,
float aAZ,
1232 float aOX,
float aOY,
float aOZ);
1234 void SetPosition(
float aX,
float aY,
float aZ);
1237 void VectorMove(
float aX,
float aY,
float aZ,
float aLength);
1255 void Subscribe(uint32_t aIndex);
1268 uint32_t
GetButtons()
const {
return GetVar(mDevice->buttons); };
1272 {
if (GetVar(mDevice->axes_count) <= (int32_t)aIndex)
return -1.0;
return GetVar(mDevice->pos[aIndex]); };
1275 double operator [] (uint32_t aIndex)
const {
return GetAxes(aIndex); }
1306 void Subscribe(uint32_t aIndex);
1322 uint32_t GetMapSizeY()
const {
return GetVar(mDevice->map_size_y); };
1325 uint32_t GetMapTileX()
const {
return GetVar(mDevice->
map_tile_x); };
1326 uint32_t GetMapTileY()
const {
return GetVar(mDevice->map_tile_y); };
1348 {
return GetVar(mDevice->hypoths[aIndex]); };
1358 void SetPose(
double pose[3],
double cov[3]);
1376 void Subscribe(uint32_t aIndex);
1401 void SetState(
int aState);
1404 void SetWriteState(
int aState);
1407 void SetReadState(
int aState);
1413 void SetFilename(
const std::string aFilename);
1423 void Subscribe(uint32_t aIndex);
1441 {
return y*GetWidth() + x; };
1445 {
return GetVar(mDevice->
cells[GetCellIndex(x,y)]); };
1455 uint32_t
GetHeight()
const {
return GetVar(mDevice->height); };
1457 double GetOriginX()
const {
return GetVar(mDevice->
origin[0]); };
1458 double GetOriginY()
const {
return GetVar(mDevice->
origin[1]); };
1463 return GetVarByRef(reinterpret_cast<int8_t*>(mDevice->
cells),
1464 reinterpret_cast<int8_t*>(mDevice->
cells+GetWidth()*GetHeight()),
1479 void Subscribe(uint32_t aIndex);
1498 return GetVarByRef(mDevice->
data,
1519 void Subscribe(uint32_t aIndex);
1533 void SetGoalPose(
double aGx,
double aGy,
double aGa);
1537 void RequestWaypoints();
1541 void SetEnable(
bool aEnable);
1551 double GetPx()
const {
return GetVar(mDevice->
px); };
1554 double GetPy()
const {
return GetVar(mDevice->py); };
1557 double GetPa()
const {
return GetVar(mDevice->pa); };
1572 double GetGx()
const {
return GetVar(mDevice->
gx); };
1575 double GetGy()
const {
return GetVar(mDevice->gy); };
1578 double GetGa()
const {
return GetVar(mDevice->ga); };
1593 double GetWx()
const {
return GetVar(mDevice->
wx); };
1596 double GetWy()
const {
return GetVar(mDevice->wy); };
1599 double GetWa()
const {
return GetVar(mDevice->wa); };
1614 double GetIx(
int i)
const;
1617 double GetIy(
int i)
const;
1620 double GetIa(
int i)
const;
1625 assert(aIndex < GetWaypointCount());
1649 {
return GetWaypoint(aIndex); }
1660 void Subscribe(uint32_t aIndex);
1678 {
return GetVar(mDevice->
points[aIndex]); };
1696 void Subscribe(uint32_t aIndex);
1712 void SetSpeed(
double aVel);
1717 void GoTo(
double aPos,
double aVel);
1739 b.
sl = mDevice->size[0];
1740 b.
sw = mDevice->size[1];
1748 void SetMotorEnable(
bool enable);
1752 void SetOdometry(
double aPos);
1781 {
return (GetVar(mDevice->
status) &
1786 {
return (GetVar(mDevice->
status) &
1791 {
return (GetVar(mDevice->
status) &
1796 {
return (GetVar(mDevice->
status) &
1801 {
return (GetVar(mDevice->
status) &
1806 {
return (GetVar(mDevice->
status) &
1820 void Subscribe(uint32_t aIndex);
1836 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aYawSpeed);
1841 {
return SetSpeed(aXSpeed, 0, aYawSpeed);}
1845 {
return SetSpeed(vel.
px, vel.
py, vel.
pa);}
1850 void SetVelHead(
double aXSpeed,
double aYSpeed,
double aYawHead);
1855 {
return SetVelHead(aXSpeed, 0, aYawHead);}
1869 void GoTo(
double aX,
double aY,
double aYaw)
1873 void SetCarlike(
double aXSpeed,
double aDriveAngle);
1896 b.
sl = mDevice->size[0];
1897 b.
sw = mDevice->size[1];
1905 void SetMotorEnable(
bool enable);
1918 void ResetOdometry();
1926 void SetOdometry(
double aX,
double aY,
double aYaw);
1957 double GetYPos()
const {
return GetVar(mDevice->py); };
1960 double GetYaw()
const {
return GetVar(mDevice->pa); };
1987 void Subscribe(uint32_t aIndex);
2003 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aZSpeed,
2004 double aRollSpeed,
double aPitchSpeed,
double aYawSpeed);
2010 double aZSpeed,
double aYawSpeed)
2011 { SetSpeed(aXSpeed,aYSpeed,aZSpeed,0,0,aYawSpeed); }
2014 void SetSpeed(
double aXSpeed,
double aYSpeed,
double aYawSpeed)
2015 { SetSpeed(aXSpeed, aYSpeed, 0, 0, 0, aYawSpeed); }
2020 { SetSpeed(aXSpeed,0,0,0,0,aYawSpeed);}
2038 void GoTo(
double aX,
double aY,
double aZ,
2039 double aRoll,
double aPitch,
double aYaw)
2049 void SetMotorEnable(
bool aEnable);
2053 void SelectVelocityControl(
int aMode);
2056 void ResetOdometry();
2061 void SetOdometry(
double aX,
double aY,
double aZ,
2062 double aRoll,
double aPitch,
double aYaw);
2086 double GetYPos()
const {
return GetVar(mDevice->pos_y); };
2089 double GetZPos()
const {
return GetVar(mDevice->pos_z); };
2095 double GetPitch()
const {
return GetVar(mDevice->pos_pitch); };
2098 double GetYaw()
const {
return GetVar(mDevice->pos_yaw); };
2104 double GetYSpeed()
const {
return GetVar(mDevice->vel_y); };
2107 double GetZSpeed()
const {
return GetVar(mDevice->vel_z); };
2127 void Subscribe(uint32_t aIndex);
2155 bool IsValid()
const {
return GetVar(mDevice->
valid) != 0 ?
true :
false;};
2169 void Subscribe(uint32_t aIndex);
2186 void SetCam(
double aPan,
double aTilt,
double aZoom);
2189 void SetSpeed(
double aPanSpeed=0,
double aTiltSpeed=0,
double aZoomSpeed=0);
2193 void SelectControlMode(uint32_t aMode);
2198 double GetTilt()
const {
return GetVar(mDevice->tilt); };
2214 void Subscribe(uint32_t aIndex);
2242 double GetRange(uint32_t aIndex)
const;
2244 double operator[] (uint32_t aIndex)
const {
return GetRange(aIndex); }
2249 double GetIntensity(uint32_t aIndex)
const;
2253 void SetPower(
bool aEnable);
2257 void SetIntensityData(
bool aEnable);
2266 void Configure(
double aMinAngle,
2276 void RequestConfigure();
2307 void Subscribe(uint32_t aIndex);
2323 {
return GetVar(mDevice->
tags[aIndex]);};
2330 {
return(GetRFIDTag(aIndex)); }
2341 void Subscribe(uint32_t aIndex);
2355 void SetPose2d(
char* identifier,
double x,
double y,
double a);
2359 void GetPose2d(
char* identifier,
double& x,
double& y,
double& a);
2363 void SetPose3d(
char* identifier,
double x,
double y,
double z,
2364 double roll,
double pitch,
double yaw);
2368 void GetPose3d(
char* identifier,
double& x,
double& y,
double& z,
2369 double& roll,
double& pitch,
double& yaw,
double& time);
2372 void GetProperty(
char* identifier,
char *name,
void *value,
size_t value_len );
2375 void SetProperty(
char* identifier,
char *name,
void *value,
size_t value_len );
2388 void Subscribe(uint32_t aIndex);
2405 {
if (GetVar(mDevice->
scan_count) <= (int32_t)aIndex)
return -1.0;
return GetVar(mDevice->
scan[aIndex]); };
2408 double operator [] (uint32_t aIndex)
const {
return GetScan(aIndex); }
2415 {
return GetVar(mDevice->
poses[aIndex]); };
2437 void Subscribe(uint32_t aIndex);
2451 void Say(std::string aStr);
2459 void Subscribe(uint32_t aIndex);
2471 return std::string(mDevice->words[aWord]);
2475 uint32_t
GetCount(
void)
const {
return GetVar(mDevice->wordCount); }
2479 std::string operator [](uint32_t aWord) {
return(GetWord(aWord)); }
2491 void Subscribe(uint32_t aIndex);
2498 bool map_info_cached;
2506 void GetLayerData(
unsigned layer_index);
2508 int GetLayerCount()
const;
2509 std::vector<std::string> GetLayerNames()
const;
2510 int GetFeatureCount(
unsigned layer_index)
const;
2511 const uint8_t * GetFeatureData(
unsigned layer_index,
unsigned feature_index)
const;
2512 size_t GetFeatureDataCount(
unsigned layer_index,
unsigned feature_index)
const;
2522 void Subscribe(uint32_t aIndex);
2536 int GetLinkCount()
const {
return mDevice->link_count; };
2537 char* GetOwnIP()
const {
return mDevice->ip; };
2539 char* GetLinkIP(
int index)
const {
return (
char*) mDevice->
links[index].
ip; };
2540 char* GetLinkMAC(
int index)
const {
return (
char*) mDevice->
links[index].
mac; };
2541 char* GetLinkESSID(
int index)
const {
return (
char*)mDevice->
links[index].
essid; };
2542 double GetLinkFreq(
int index)
const {
return mDevice->
links[index].
freq;};
2543 int GetLinkMode(
int index)
const {
return mDevice->
links[index].
mode; };
2544 int GetLinkEncrypt(
int index)
const {
return mDevice->
links[index].
encrypt; };
2545 int GetLinkQuality(
int index)
const {
return mDevice->
links[index].
qual; };
2546 int GetLinkLevel(
int index)
const {
return mDevice->
links[index].level; };
2547 int GetLinkNoise(
int index)
const {
return mDevice->
links[index].noise; } ;
2590 void Subscribe(uint32_t aIndex);
2602 uint32_t GetNodeType ()
const {
return GetVar(mDevice->
node_type); };
2603 uint32_t GetNodeID ()
const {
return GetVar(mDevice->
node_id); };
2604 uint32_t GetNodeParentID()
const {
return GetVar(mDevice->
node_parent_id); };
2607 GetNodeDataPacket()
const {
return GetVar(mDevice->
data_packet); };
2609 void SetDevState(
int nodeID,
int groupID,
int devNr,
int value);
2610 void Power(
int nodeID,
int groupID,
int value);
2611 void DataType(
int value);
2612 void DataFreq(
int nodeID,
int groupID,
float frequency);
2620 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_point_2d_t& c);
2621 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_pose2d_t& c);
2622 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_pose3d_t& c);
2623 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_bbox2d_t& c);
2624 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_bbox3d_t& c);
2625 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_segment_t& c);
2626 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const player_extent2d_t& c);
2631 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::AioProxy& c);
2637 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::DioProxy& c);
2639 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::GpsProxy& c);
2641 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::ImuProxy& c);
2642 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::IrProxy& c);
2644 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::LimbProxy& c);
2647 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::LogProxy& c);
2648 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::MapProxy& c);
2655 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::PtzProxy& c);
2663 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::WiFiProxy& c);
2664 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::RFIDProxy& c);
2665 PLAYERCC_EXPORT std::ostream& operator << (std::ostream& os,
const PlayerCc::WSNProxy& c);
player_bbox3d_t GetOuterSize() const
Get the outer size of the gripper.
Definition: playerc++.h:847
Fiducial finder data.
Definition: playerc.h:1510
double GetBearing(uint32_t aIndex) const
get the bearing
Definition: playerc++.h:1093
Structure describing the WSN node's data packet.
Definition: player_interfaces.h:4335
The PlannerProxy proxy provides an interface to a 2D motion planner.
Definition: playerc++.h:1514
Opaque device data.
Definition: playerc.h:2459
double charge
Battery charge (Volts).
Definition: playerc.h:2890
double vel_roll
Angular velocity (radians/sec).
Definition: playerc.h:2797
uint32_t node_parent_id
The ID of the WSN node's parent (if existing).
Definition: playerc.h:3620
int GetState() const
Is logging/playback enabled? Call QueryState() to fill it.
Definition: playerc++.h:1394
int width
Map size, in cells.
Definition: playerc.h:2350
uint32_t GetBeams() const
Get the gripper break beam info.
Definition: playerc++.h:843
Planner device data.
Definition: playerc.h:2508
The AudioProxy class controls an audio device.
Definition: playerc++.h:245
player_pose3d_t GetPose(uint32_t aIndex) const
get a particular pose
Definition: playerc++.h:1006
Ir proxy data.
Definition: playerc.h:1865
RFID proxy data.
Definition: playerc.h:3433
Aio proxy data.
Definition: playerc.h:929
double GetResolution() const
Map resolution, m/cell.
Definition: playerc++.h:1448
int mode
Mode (master, ad-hoc, etc).
Definition: playerc.h:3214
uint32_t GetPoseCount() const
get the number of poses
Definition: playerc++.h:1004
data
Definition: player_interfaces.h:3414
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1159
double gx
Goal location (m, m, radians)
Definition: playerc.h:2523
double pose[3]
Robot geometry in robot cs: pose gives the position2d and orientation, size gives the extent...
Definition: playerc.h:2689
double GetYaw() const
Accessor method.
Definition: playerc++.h:2098
player_pose3d_t GetPose(uint32_t aIndex) const
Sonar poses (m,m,radians)
Definition: playerc++.h:2414
uint32_t GetHeight() const
Map size, in cells.
Definition: playerc++.h:1455
Vectormap proxy.
Definition: playerc.h:2398
double ppitch
pitch [rad]
Definition: player.h:235
The SimulationProxy proxy provides access to a simulation device.
Definition: playerc++.h:2337
uint32_t details_count
number of tones in list
Definition: player_interfaces.h:1575
double alt
Altitude (meters).
Definition: playerc.h:1576
Vectormap feature data.
Definition: player.h:261
A rectangular bounding box, used to define the size of an object.
Definition: player.h:250
void SetSpeed(player_pose2d_t vel)
Overloaded SetSpeed that takes player_pose2d_t as an argument.
Definition: playerc++.h:1844
double MinRight() const
Definition: playerc++.h:1182
Data: calibrated IMU data (PLAYER_IMU_DATA_CALIB)
Definition: player_interfaces.h:4670
double robot_pose[3]
Robot pose (m,m,rad), filled in if the scan came with a pose attached.
Definition: playerc.h:1971
uint32_t GetHeight() const
get the height of the image
Definition: playerc++.h:444
uint32_t GetNumHypoths() const
Get the number of localization hypoths.
Definition: playerc++.h:1361
Note: the structure describing the WSN node's data packet is declared in Player.
Definition: playerc.h:3610
The LimbProxy class is used to control a limb device.
Definition: playerc++.h:1199
player_bbox3d_t GetDeviceSize() const
Return the device size.
Definition: playerc++.h:2232
double GetMaxRange() const
Max range for the latest set of data (meters)
Definition: playerc++.h:1051
The GpsProxy class is used to control a gps device.
Definition: playerc++.h:679
Structure describing a single RFID tag.
Definition: playerc.h:3422
uint8_t state
The gripper's state: may be one of PLAYER_GRIPPER_STATE_OPEN, PLAYER_GRIPPER_STATE_CLOSED, PLAYER_GRIPPER_STATE_MOVING or PLAYER_GRIPPER_STATE_ERROR.
Definition: playerc.h:1763
int width
Image dimensions (pixels).
Definition: playerc.h:1401
int pending_count
The number of pending (unprocessed) sensor readings.
Definition: playerc.h:2231
int scan_count
Number of points in the scan.
Definition: playerc.h:1977
A rectangular bounding box, used to define the origin and bounds of an object.
Definition: player.h:303
Individual link info.
Definition: playerc.h:3202
double px
Odometric pose (m, m, rad).
Definition: playerc.h:2693
int sat_count
Number of satellites in view.
Definition: playerc.h:1594
int GetIntensity(uint32_t aIndex) const
get the intensity
Definition: playerc++.h:1098
player_orientation_3d_t GetBaseOrientation(void) const
Accessor method for getting the base orientation.
Definition: playerc++.h:193
void GetData(uint8_t *aDest) const
Opaque data.
Definition: playerc++.h:1496
Localization device data.
Definition: playerc.h:2213
int image_count
Size of image data (bytes)
Definition: playerc.h:1418
player_point_2d_t * point
Scan data; x, y position (m).
Definition: playerc.h:2001
int state
Is logging/playback enabled? Call playerc_log_get_state() to fill it.
Definition: playerc.h:2292
Player audio sequence item.
Definition: player_interfaces.h:1484
player_pose3d_t GetSensorPose() const
The pose of the sensor.
Definition: playerc++.h:654
player_audio_mixer_channel_t GetChannel(int aIndex) const
Get Sequence item.
Definition: playerc++.h:291
player_audio_wav_t wav_data
last block of recorded data
Definition: playerc.h:1089
double watts
power currently being used (Watts).
Definition: playerc.h:2900
int32_t default_input
default input channel (-1 for none)
Definition: player_interfaces.h:1581
A color descriptor.
Definition: player.h:316
double err_horz
Horizontal and vertical error (meters).
Definition: playerc.h:1588
void SetSpeed(player_pose3d_t vel)
Overloaded SetSpeed that takes player_pose3d_t as input.
Definition: playerc++.h:2023
The Position3dProxy class is used to control a interface_position3d device.
Definition: playerc++.h:1982
Actuator geometry.
Definition: player_interfaces.h:3786
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition: playerc.h:2696
float * voltages
voltages [V]
Definition: player_interfaces.h:2118
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition: playerc.h:3570
double GetXPos() const
Accessor method.
Definition: playerc++.h:2083
uint8_t num_beams
The number of breakbeams the gripper has.
Definition: playerc.h:1756
uint32_t GetDefaultOutputChannel() const
Get Default output Channel.
Definition: playerc++.h:266
double GetMaxRange() const
Maximum detectable range of a scan (configured value)
Definition: playerc++.h:2291
int intensity_on
Is intesity data returned.
Definition: playerc.h:1974
void SetSpeed(double aXSpeed, double aYSpeed, double aYawSpeed)
simplified version of SetSpeed
Definition: playerc++.h:2014
bool GetStall() const
Accessor method.
Definition: playerc++.h:1972
pointcloud3d proxy data.
Definition: playerc.h:3474
double pos_x
Device position (m).
Definition: playerc.h:2788
The RangerProxy class is used to control a ranger device.
Definition: playerc++.h:2210
uint32_t GetNumBeams() const
Get the number of breakbeams in the gripper.
Definition: playerc++.h:851
double GetUtmEasting() const
UTM easting and northing (meters).
Definition: playerc++.h:717
double lat
Latitude and logitude (degrees).
Definition: playerc.h:1572
Camera proxy data.
Definition: playerc.h:1395
double GetVoltage(uint32_t aIndex) const
Accessor function.
Definition: playerc++.h:226
int GetCellIndex(int x, int y) const
Return the index of the (x,y) item in the cell array.
Definition: playerc++.h:1440
double GetYSpeed() const
Accessor method.
Definition: playerc++.h:1966
The VectorMapProxy class is used to interface to a vectormap.
Definition: playerc++.h:2485
double px
X [m].
Definition: player.h:216
double scan_start
Start bearing of the scan (radians).
Definition: playerc.h:1980
uint32_t GetState(void) const
Get driver state.
Definition: playerc++.h:293
bool GetCharging() const
Returns whether charging is taking place.
Definition: playerc++.h:2152
double px
Current pose (m, m, radians).
Definition: playerc.h:2520
double GetGa() const
Goal location (radians)
Definition: playerc++.h:1578
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:1840
int path_valid
Did the planner find a valid path?
Definition: playerc.h:2514
The map proxy provides access to a map device.
Definition: playerc++.h:1419
Simulation device proxy.
Definition: playerc.h:3272
Speech recognition proxy data.
Definition: playerc.h:3384
uint32_t tones_count
number of tones in list
Definition: player_interfaces.h:1505
double GetVel() const
Accessor method.
Definition: playerc++.h:1771
player_audio_mixer_channel_detail_t GetMixerDetails(int aIndex) const
Get Mixer Detail.
Definition: playerc++.h:264
player_pose3d_t * poses
Pose of each sonar relative to robot (m, m, radians).
Definition: playerc.h:3157
#define PLAYER_POSITION1D_STATUS_LIMIT_MIN
Status byte: limit min.
Definition: player_interfaces.h:3491
uint32_t GetCapacity() const
Get the capacity of the gripper's storage.
Definition: playerc++.h:853
double pan
The current ptz pan and tilt angles.
Definition: playerc.h:2945
double GetWx() const
Current waypoint location (m)
Definition: playerc++.h:1593
double py
Y [m].
Definition: player.h:229
#define PLAYER_POSITION1D_STATUS_LIMIT_MAX
Status byte: limit max.
Definition: player_interfaces.h:3495
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition: playerc.h:3480
double GetVdop() const
Vertical dilution of position (HDOP)
Definition: playerc++.h:714
double GetWatts() const
Returns the watts.
Definition: playerc++.h:2149
double GetConfMinAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition: playerc++.h:1072
double scanning_frequency
Scanning frequency in Hz.
Definition: playerc.h:1992
A pose in the plane.
Definition: player.h:213
uint32_t data_count
length of raw data
Definition: player_interfaces.h:1469
double GetVoltage(uint32_t aIndex) const
get the current voltage
Definition: playerc++.h:1001
uint8_t GetStatus() const
Accessor method.
Definition: playerc++.h:1777
double GetLatitude() const
Latitude and longitude, in degrees.
Definition: playerc++.h:698
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition: playerc.h:1355
bool IsTrajComplete() const
Accessor method.
Definition: playerc++.h:1800
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam...
Definition: playerc.h:2017
double freq
Frequency (MHz).
Definition: playerc.h:3220
double min_angle
Start angle of scans [rad].
Definition: playerc.h:3028
The HealthProxy class is used to get infos of the player-server.
Definition: playerc++.h:871
double GetScanningFrequency() const
Scanning Frequency (Hz)
Definition: playerc++.h:1060
uint32_t GetPathValid() const
Did the planner find a valid path?
Definition: playerc++.h:1544
bool IsLimitMin() const
Accessor method.
Definition: playerc++.h:1780
double GetPa() const
Current pose (radians)
Definition: playerc++.h:1557
Graphics3d device data.
Definition: playerc.h:1685
double GetXSpeed() const
Accessor method.
Definition: playerc++.h:2101
player_bbox2d_t GetFiducialSize() const
The size of the most recently detected fiducial.
Definition: playerc++.h:662
player_point_3d_t GetBasePos(void) const
Accessor method for getting the base position.
Definition: playerc++.h:191
uint32_t GetNumParticles() const
Get the number of particles (for particle filter-based localization systems).
Definition: playerc++.h:1365
uint32_t GetHypothCount() const
Number of possible poses.
Definition: playerc++.h:1344
int data_count
Size of data (bytes)
Definition: playerc.h:2465
Definition: playerclient.h:305
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc.h:2288
double pos
Odometric pose [m] or [rad].
Definition: playerc.h:2599
uint32_t poses_count
the number of ir samples returned by this robot
Definition: player_interfaces.h:2131
An angle in 3D space.
Definition: player.h:202
double frequency
Scanning frequency [Hz].
Definition: playerc.h:3041
int pose_count
Number of pose values.
Definition: playerc.h:1344
Power device data.
Definition: playerc.h:2880
double pose[3]
Laser geometry in the robot cs: pose gives the position and orientation, size gives the extent...
Definition: playerc.h:1967
uint32_t GetWavDataLength() const
Get Wav data length.
Definition: playerc++.h:271
double GetAxes(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:1271
The Pointcloud3d proxy provides an interface to a pointcloud3d device.
Definition: playerc++.h:1656
double GetRangeRes() const
Linear resolution (configured value)
Definition: playerc++.h:2294
void GetImage(uint8_t *aImage) const
Image data This function copies the image data into the data buffer aImage.
Definition: playerc++.h:570
The GripperProxy class is used to control a gripper device.
Definition: playerc++.h:818
double vel
Odometric velocity [m/s] or [rad/s].
Definition: playerc.h:2602
The OpaqueProxy proxy provides an interface to a generic opaque.
Definition: playerc++.h:1474
uint32_t GetWaypointCount() const
Number of waypoints in the plan.
Definition: playerc++.h:1641
double resolution
Map resolution, m/cell.
Definition: playerc.h:2347
double joules
energy stored (Joules)
Definition: playerc.h:2896
double GetPercent() const
Returns the percent of power.
Definition: playerc++.h:2143
int valid
status bits.
Definition: playerc.h:2887
player_audio_mixer_channel_t * channels
the channels
Definition: player_interfaces.h:1538
bool IsEnabled() const
Accessor method.
Definition: playerc++.h:1805
void GoTo(player_pose2d_t pos)
Same as the previous GoTo(), but doesn't take speed.
Definition: playerc++.h:1864
double utc_time
UTC time (seconds since the epoch)
Definition: playerc.h:1567
double GetScanRes() const
Angular resolution of scan (radians)
Definition: playerc++.h:1054
Gripper device data.
Definition: playerc.h:1741
int map_size_x
Map dimensions (cells).
Definition: playerc.h:2219
double GetZSpeed() const
Accessor method.
Definition: playerc++.h:2107
The BlackBoardProxy class is used to subscribe to a blackboard device.
Definition: playerc++.h:346
Data: state (PLAYER_LIMB_DATA)
Definition: player_interfaces.h:4037
Structure containing a single actuator's information.
Definition: player_interfaces.h:3758
Map proxy data.
Definition: playerc.h:2341
double max_range
Maximum range [m].
Definition: playerc.h:3037
uint32_t GetPendingCount() const
Number of pending (unprocessed) sensor readings.
Definition: playerc++.h:1341
int charging
charging flag.
Definition: playerc.h:2903
Request/reply: get geometry.
Definition: player_interfaces.h:4112
double GetFrequency() const
Scanning frequency (configured value)
Definition: playerc++.h:2297
double max_angle
End angle of scans [rad].
Definition: playerc.h:3030
double GetMinRange() const
Minimum detectable range of a scan (configured value)
Definition: playerc++.h:2288
uint32_t IsBumped(uint32_t aIndex) const
Returns true if the specified bumper has been bumped, false otherwise.
Definition: playerc++.h:489
The Position2dProxy class is used to control a position2d device.
Definition: playerc++.h:1815
double GetXSpeed() const
Accessor method.
Definition: playerc++.h:1963
Position3d device data.
Definition: playerc.h:2776
Info about an available (but not necessarily subscribed) device.
Definition: playerc.h:448
int hypoth_count
List of possible poses.
Definition: playerc.h:2237
double range_res
Range resolution [m].
Definition: playerc.h:3039
The PtzProxy class is used to control a ptz device.
Definition: playerc++.h:2164
player_audio_seq_t seq_data
last block of seq data
Definition: playerc.h:1092
double GetMaxAngle() const
Stop angle of a scan (configured value)
Definition: playerc++.h:2282
A point in the plane.
Definition: player.h:180
double pose[3]
Robot geometry in robot cs: pose gives the position1d and orientation, size gives the extent...
Definition: playerc.h:2595
double(* waypoints)[3]
List of waypoints in the current plan (m,m,radians).
Definition: playerc.h:2538
int GetCurrentWaypointId() const
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc++.h:1637
player_audio_mixer_channel_list_detail_t channel_details_list
Details of the channels from the mixer.
Definition: playerc.h:1086
double GetJoules() const
Returns the joules.
Definition: playerc++.h:2146
Ranger proxy data.
Definition: playerc.h:3019
bool GetStall() const
Accessor method.
Definition: playerc++.h:1774
double GetMinLeft() const
Minimum range reading on the left side.
Definition: playerc++.h:1170
double GetRange(uint32_t aIndex) const
get the range
Definition: playerc++.h:1089
player_bbox2d_t fiducial_size
Dimensions of the fiducials in units of (m).
Definition: player_interfaces.h:1724
uint32_t GetCount() const
Number of points in scan.
Definition: playerc++.h:1048
player_pose3d_t device_pose
Device geometry in the robot CS: pose gives the position and orientation, size gives the extent...
Definition: playerc.h:3046
double GetYPos() const
Accessor method.
Definition: playerc++.h:2086
int32_t default_output
default output channel (-1 for none)
Definition: player_interfaces.h:1579
The PlayerClient is used for communicating with the player server.
Definition: playerclient.h:115
double GetCharge() const
Returns the current charge.
Definition: playerc++.h:2140
double map_scale
Map scale (m/cell).
Definition: playerc.h:2222
player_pose2d_t GetGoal() const
Get the goal.
Definition: playerc++.h:1581
bool IsOverCurrent() const
Accessor method.
Definition: playerc++.h:1795
int quality
Quality of fix 0 = invalid, 1 = GPS fix, 2 = DGPS fix.
Definition: playerc.h:1591
The SpeechProxy class is used to control a speech device.
Definition: playerc++.h:2432
double sw
Width [m].
Definition: player.h:253
double GetWa() const
Current waypoint location (rad)
Definition: playerc++.h:1599
player_pose3d_t * poses
the pose of each IR detector on this robot
Definition: player_interfaces.h:2133
The client proxy base class.
Definition: clientproxy.h:79
double GetMinAngle() const
Start angle of a scan (configured value)
Definition: playerc++.h:2279
player_pose3d_t GetDevicePose() const
Return the device pose.
Definition: playerc++.h:2230
The ImuProxy class is used to control an imu device.
Definition: playerc++.h:931
double max_range
Maximum range of sensor, in m.
Definition: playerc.h:1989
double px
X [m].
Definition: player.h:227
uint8_t capacity
The capacity of the gripper's store - if 0, the gripper cannot store.
Definition: playerc.h:1758
int GetParticles()
Get the particle set.
Definition: playerc++.h:1351
player_bbox3d_t size
Size of the detector.
Definition: player_interfaces.h:1722
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:1854
double GetTime() const
Time, since the epoch.
Definition: playerc++.h:721
The WiFiProxy class controls a wifi device.
Definition: playerc++.h:2517
double GetYPos() const
Accessor method.
Definition: playerc++.h:1957
uint32_t GetAxesCount() const
Number of valid joystick poses.
Definition: playerc++.h:1278
PTZ device data.
Definition: playerc.h:2937
player_pose2d_t GetPose() const
Get the current pose.
Definition: playerc++.h:1560
int bumper_count
Number of points in the scan.
Definition: playerc.h:1352
double GetZPos() const
Accessor method.
Definition: playerc++.h:2089
int stall
Stall flag [0, 1].
Definition: playerc.h:2699
double GetGy() const
Goal location (m)
Definition: playerc++.h:1575
double pa
yaw [rad]
Definition: player.h:220
void GoTo(player_pose3d_t aPos)
Same as the previous GoTo(), but does'n take vel argument.
Definition: playerc++.h:2032
Player audio sequence.
Definition: player_interfaces.h:1502
uint32_t GetElementCount() const
Return the individual range sensor count.
Definition: playerc++.h:2227
uint32_t GetWidth() const
get the width of the image
Definition: playerc++.h:442
player_fiducial_item_t GetFiducialItem(uint32_t aIndex) const
Get detected beacon description.
Definition: playerc++.h:650
double scan_res
Angular resolution in radians.
Definition: playerc.h:1983
int path_done
Have we arrived at the goal?
Definition: playerc.h:2517
double angular_res
Scan resolution [rad].
Definition: playerc.h:3032
uint32_t GetChannelCount() const
Get Channel data count.
Definition: playerc++.h:289
double MinLeft() const
Definition: playerc++.h:1178
A rectangular bounding box, used to define the size of an object.
Definition: player.h:241
double * ranges
Raw range data; range (m).
Definition: playerc.h:1995
double GetZoom() const
Return Zoom.
Definition: playerc++.h:2200
player_localize_hypoth_t GetHypoth(uint32_t aIndex) const
Array of possible poses.
Definition: playerc++.h:1347
double range_res
Range resolution, in m.
Definition: playerc.h:1986
double GetMinAngle() const
Scan range for the latest set of data (radians)
Definition: playerc++.h:1063
double GetXPos() const
Set PID terms.
Definition: playerc++.h:1954
Speech proxy data.
Definition: playerc.h:3348
Position1d device data.
Definition: playerc.h:2587
uint32_t actuators_count
The number of actuators in the array.
Definition: playerc.h:992
double GetRange(uint32_t aIndex) const
get the current range
Definition: playerc++.h:998
player_pose3d_t GetPose() const
get the processed pos of the imu
Definition: playerc++.h:948
The RFIDProxy class is used to control a rfid device.
Definition: playerc++.h:2302
uint32_t GetImageSize() const
Size of the image (bytes)
Definition: playerc++.h:564
uint32_t GetCount() const
How long is the data?
Definition: playerc++.h:1493
uint32_t GetHeight() const
Image dimensions (pixels)
Definition: playerc++.h:553
std::string GetWord(uint32_t aWord) const
Accessor method for getting speech recognition data i.e. words.
Definition: playerc++.h:2469
double utm_e
UTM easting and northing (meters).
Definition: playerc.h:1579
player_bbox3d_t GetSize()
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1892
GPS proxy data.
Definition: playerc.h:1561
uint32_t beams
The position of the object in the gripper.
Definition: playerc.h:1765
uint32_t GetDefaultInputChannel() const
Get Default input Channel.
Definition: playerc++.h:268
double GetRollSpeed() const
Accessor method.
Definition: playerc++.h:2110
bool IsLimitCen() const
Accessor method.
Definition: playerc++.h:1785
uint32_t GetFormat() const
Image format Possible values include.
Definition: playerc++.h:561
The BumperProxy class is used to read from a bumper device.
Definition: playerc++.h:470
double GetConfMaxAngle() const
Scan range from the laser config (call RequestConfigure first) (radians)
Definition: playerc++.h:1074
Audio device data.
Definition: playerc.h:1080
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition: playerc.h:1752
player_pose2d_t GetWaypoint(uint32_t aIndex) const
Get the waypoint.
Definition: playerc++.h:1623
Definition: playerclient.h:90
int qual
Link properties.
Definition: playerc.h:3223
player_pose3d_t pose
The complete pose of the IMU in 3D coordinates + angles.
Definition: playerc.h:3565
Sonar proxy data.
Definition: playerc.h:3147
Note: the structure describing the HEALTH's data packet is declared in Player.
Definition: playerc.h:1824
double GetMinRight() const
Minimum range reading on the right side.
Definition: playerc++.h:1174
uint8_t mac[32]
Mac accress.
Definition: playerc.h:3205
uint32_t element_count
Number of individual elements in the device.
Definition: playerc.h:3025
float * ranges
ranges [m]
Definition: player_interfaces.h:2122
player_bbox3d_t GetSensorSize() const
The size of the sensor.
Definition: playerc++.h:658
uint32_t GetMixerDetailsCount() const
Get Mixer Details Count.
Definition: playerc++.h:262
double zoom
The current zoom value (field of view angle).
Definition: playerc.h:2948
The LinuxjoystickProxy class is used to control a joystick device.
Definition: playerc++.h:1251
void SetSpeed(double aXSpeed, double aYSpeed, double aZSpeed, double aYawSpeed)
Send a motor command for a planar robot.
Definition: playerc++.h:2009
uint32_t GetPoseCount() const
Number of valid sonar poses.
Definition: playerc++.h:2411
double GetAngularRes() const
Angular resolution of a scan (configured value)
Definition: playerc++.h:2285
uint32_t GetIntensityCount() const
Return the number of intensity readings.
Definition: playerc++.h:2247
uint8_t stored
The number of currently-stored objects.
Definition: playerc.h:1767
void GoTo(double aX, double aY, double aZ, double aRoll, double aPitch, double aYaw)
Same as the previous GoTo(), but only takes position arguments, no motion speed setting.
Definition: playerc++.h:2038
unsigned int blobs_count
A list of detected blobs.
Definition: playerc.h:1304
playerc_rfidtag_t * tags
The list of RFID tags.
Definition: playerc.h:3442
uint32_t GetTagsCount() const
returns the number of RFID tags
Definition: playerc++.h:2320
double GetYSpeed() const
Accessor method.
Definition: playerc++.h:2104
player_pose3d_t GetPose() const
Get the pose of the gripper.
Definition: playerc++.h:845
uint32_t GetMapSizeX() const
Map dimensions (cells)
Definition: playerc++.h:1321
player_pose3d_t GetRobotPose()
Accessor for the pose of the laser's parent object (e.g., a robot).
Definition: playerc++.h:1147
uint32_t intensities_count
Number of intensities in a scan.
Definition: playerc.h:3060
The SpeechRecognition proxy provides access to a speech_recognition device.
Definition: playerc++.h:2457
player_fiducial_geom_t fiducial_geom
Geometry in robot cs.
Definition: playerc.h:1519
int8_t GetCell(int x, int y) const
Get the (x,y) cell.
Definition: playerc++.h:1444
Blobfinder device data.
Definition: playerc.h:1295
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc.h:2531
uint32_t GetQuality() const
Fix quality.
Definition: playerc++.h:708
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
The BlinkenlightProxy class is used to enable and disable a flashing indicator light, and to set its period, via a blinkenlight device.
Definition: playerc++.h:419
double pyaw
yaw [rad]
Definition: player.h:237
uint32_t ranges_count
number of samples
Definition: player_interfaces.h:2120
double sl
Length [m].
Definition: player.h:255
uint32_t GetDepth() const
Image color depth.
Definition: playerc++.h:547
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:2022
The PowerProxy class controls a power device.
Definition: playerc++.h:2123
Graphics2d device data.
Definition: playerc.h:1625
int fiducials_count
List of detected beacons.
Definition: playerc.h:1522
uint32_t ranges_count
Number of ranges in a scan.
Definition: playerc.h:3055
uint32_t GetButtons() const
return the sensor count
Definition: playerc++.h:1268
player_audio_seq_item_t GetSeqItem(int aIndex) const
Get Sequence item.
Definition: playerc++.h:286
uint32_t GetCount() const
get the number of IR rangers
Definition: playerc++.h:996
uint32_t GetCompression() const
What is the compression type? Currently supported compression types are:
Definition: playerc++.h:581
void SetSpeed(double aXSpeed, double aYawSpeed)
Same as the previous SetSpeed(), but doesn't take the sideways speed (so use this one for non-holonom...
Definition: playerc++.h:2019
playerc_rfidtag_t GetRFIDTag(uint32_t aIndex) const
returns a RFID tag
Definition: playerc++.h:2322
playerc_wifi_link_t * links
A list containing info for each link.
Definition: playerc.h:3235
double * scan
Scan data: range (m).
Definition: playerc.h:3163
double GetPitch() const
Accessor method.
Definition: playerc++.h:2095
uint32_t GetRangeCount() const
Return the number of range readings.
Definition: playerc++.h:2240
The LaserProxy class is used to control a laser device.
Definition: playerc++.h:1026
uint32_t GetCount(void) const
Gets the number of actuators in the array.
Definition: playerc++.h:185
uint32_t channels_count
number of channels in list
Definition: player_interfaces.h:1536
int bpp
Image bits-per-pixel (8, 16, 24).
Definition: playerc.h:1404
The LogProxy proxy provides access to a log device.
Definition: playerc++.h:1372
The LocalizeProxy class is used to control a localize device, which can provide multiple pose hypothe...
Definition: playerc++.h:1301
double(* scan)[2]
Scan data; range (m) and bearing (radians).
Definition: playerc.h:1998
int GetType() const
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc++.h:1391
int encrypt
Encrypted?
Definition: playerc.h:3217
double GetPx() const
Current pose (m)
Definition: playerc++.h:1551
Bumper proxy data.
Definition: playerc.h:1338
Log proxy data.
Definition: playerc.h:2281
double GetYawSpeed() const
Accessor method.
Definition: playerc++.h:2116
uint32_t GetSatellites() const
Number of satellites in view.
Definition: playerc++.h:705
double hdop
Horizontal dilution of precision.
Definition: playerc.h:1582
double GetRoll() const
Accessor method.
Definition: playerc++.h:2092
uint32_t GetCount() const
returns the number of blobs
Definition: playerc++.h:436
void GoTo(double aX, double aY, double aYaw)
Same as the previous GoTo(), but only takes position arguments, no motion speed setting.
Definition: playerc++.h:1869
The Graphics3dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition: playerc++.h:781
player_bumper_define_t GetPose(uint32_t aIndex) const
Returns a specific bumper pose.
Definition: playerc++.h:502
int laser_id
Laser IDentification information.
Definition: playerc.h:2012
double GetPos() const
Set PID terms.
Definition: playerc++.h:1768
double GetYaw() const
Accessor method.
Definition: playerc++.h:1960
playerc_speechrecognition_t * mDevice
libplayerc data structure
Definition: playerc++.h:2463
double GetPan() const
Return Pan (rad)
Definition: playerc++.h:2196
player_pose3d_t pose
Pose of the detector in the robot cs.
Definition: player_interfaces.h:1720
void ResetOdometry()
Reset odometry to 0.
Definition: playerc++.h:1755
double origin[2]
Map origin, in meters (i.e., the real-world coordinates of cell 0,0)
Definition: playerc.h:2353
Structure describing a single blob.
Definition: player_interfaces.h:1071
double GetGx() const
Goal location (m)
Definition: playerc++.h:1572
int compression
Image compression method.
Definition: playerc.h:1415
bool IntensityOn() const
Whether or not reflectance (i.e., intensity) values are being returned.
Definition: playerc++.h:1077
3D Pointcloud element structure An element as stored in a 3D pointcloud, containing a 3D position plu...
Definition: player_interfaces.h:4798
#define PLAYER_POSITION1D_STATUS_TRAJ_COMPLETE
Status byte: limit trajectory complete.
Definition: player_interfaces.h:3499
player_bbox3d_t GetInnerSize() const
Get the inner size of the gripper.
Definition: playerc++.h:849
Position2d device data.
Definition: playerc.h:2681
Laser proxy data.
Definition: playerc.h:1959
player_pointcloud3d_element_t GetPoint(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:1677
uint32_t GetCount() const
The number of beacons detected.
Definition: playerc++.h:647
uint8_t * image
Image data (byte aligned, row major order).
Definition: playerc.h:1424
joystick proxy data.
Definition: playerc.h:1914
int map_tile_x
Next map tile to read.
Definition: playerc.h:2225
int scan_count
Number of points in the scan.
Definition: playerc.h:3160
double pos_roll
Device orientation (radians).
Definition: playerc.h:2791
player_pose2d_t GetCurrentWaypoint() const
Get the current waypoint.
Definition: playerc++.h:1602
uint16_t tags_count
The number of RFID tags found.
Definition: playerc.h:3439
player_pose3d_t GetPose() const
Accessor for the pose (fill it in by calling RequestGeom)
Definition: playerc++.h:1724
player_audio_seq_item_t * tones
the tones
Definition: player_interfaces.h:1507
Dio proxy data.
Definition: playerc.h:1461
A pose in space.
Definition: player.h:224
uint32_t GetPoseCount() const
Returns the number bumper poses.
Definition: playerc++.h:499
uint32_t GetDigin() const
A bitfield of the current digital inputs.
Definition: playerc++.h:610
uint32_t GetState() const
Get the gripper state.
Definition: playerc++.h:841
uint8_t * data
Data.
Definition: playerc.h:2468
uint32_t node_type
The type of WSN node.
Definition: playerc.h:3616
IMU proxy state data.
Definition: playerc.h:3559
double percent
Battery charge (percent full).
Definition: playerc.h:2893
uint32_t node_id
The ID of the WSN node.
Definition: playerc.h:3618
double GetHdop() const
Horizontal dilution of position (HDOP)
Definition: playerc++.h:711
bool IsLimitMax() const
Accessor method.
Definition: playerc++.h:1790
uint32_t GetCount() const
Accessor function.
Definition: playerc++.h:223
double GetScan(uint32_t aIndex) const
return a particular scan value
Definition: playerc++.h:2404
player_pose3d_t GetPose()
Accessor for the pose of the laser with respect to its parent object (e.g., a robot).
Definition: playerc++.h:1134
player_bumper_define_t * poses
Pose of each bumper relative to robot (mm, mm, deg, mm, mm).
Definition: playerc.h:1349
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition: playerc.h:1095
A point in 3D space.
Definition: player.h:190
int waypoint_count
Number of waypoints in the plan.
Definition: playerc.h:2534
Info on a single detected fiducial.
Definition: player_interfaces.h:1688
double vdop
Vertical dilution of precision.
Definition: playerc.h:1585
char * cells
Occupancy for each cell (empty = -1, unknown = 0, occupied = +1)
Definition: playerc.h:2356
The Position1dProxy class is used to control a position1d device.
Definition: playerc++.h:1691
void GetMap(int8_t *aMap) const
Occupancy for each cell (empty = -1, unknown = 0, occupied = +1)
Definition: playerc++.h:1461
#define PLAYER_POSITION1D_STATUS_OC
Status byte: limit over current.
Definition: player_interfaces.h:3497
double py
Y [m].
Definition: player.h:218
double GetYawSpeed() const
Accessor method.
Definition: playerc++.h:1969
BlackBoard proxy.
Definition: playerc.h:1178
double GetPy() const
Current pose (m)
Definition: playerc++.h:1554
The AioProxy class is used to read from a aio (analog I/O) device.
Definition: playerc++.h:207
player_point_3d_t base_pos
The position of the base of the actarray.
Definition: playerc.h:1001
The IrProxy class is used to control an ir device.
Definition: playerc++.h:977
double min_range
Minimum range [m].
Definition: playerc.h:3035
int pose_count
Number of pose values.
Definition: playerc.h:3153
bool GetStall() const
Accessor method.
Definition: playerc++.h:2119
double GetErrHorizontal() const
Errors.
Definition: playerc++.h:724
uint32_t GetSeqCount() const
Get Seq data count.
Definition: playerc++.h:284
uint8_t ip[32]
IP address.
Definition: playerc.h:3208
int stall
Stall flag [0, 1].
Definition: playerc.h:2800
player_point_2d_t GetPoint(uint32_t aIndex) const
Scan data (Cartesian): x,y (m)
Definition: playerc++.h:1084
uint32_t GetStored() const
Get the number of currently-stored objects.
Definition: playerc++.h:855
The CameraProxy class can be used to get images from a camera device.
Definition: playerc++.h:517
int * intensity
Scan reflection intensity values (0-3).
Definition: playerc.h:2006
The WSNProxy class is used to control a wsn device.
Definition: playerc++.h:2585
Player mixer channel detail.
Definition: player_interfaces.h:1555
#define PLAYER_POSITION1D_STATUS_ENABLED
Status byte: enabled.
Definition: player_interfaces.h:3501
The FiducialProxy class is used to control fiducial devices.
Definition: playerc++.h:631
unsigned int width
Image dimensions (pixels).
Definition: playerc.h:1301
double proll
roll [rad]
Definition: player.h:233
double GetWy() const
Current waypoint location (m)
Definition: playerc++.h:1596
double wx
Current waypoint location (m, m, radians)
Definition: playerc.h:2526
int format
Image format (e.g., RGB888).
Definition: playerc.h:1407
Wifi device proxy.
Definition: playerc.h:3229
double pz
Z [m].
Definition: player.h:231
player_pose3d_t GetOffset()
Accessor for the robot's pose with respect to its.
Definition: playerc++.h:1881
uint32_t GetCount() const
The number of valid digital inputs.
Definition: playerc++.h:607
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition: playerc.h:3483
uint32_t GetCount() const
return the sensor count
Definition: playerc++.h:2401
The SonarProxy class is used to control a sonar device.
Definition: playerc++.h:2384
double GetTilt() const
Return Tilt (rad)
Definition: playerc++.h:2198
double GetAltitude() const
Altitude, in meters.
Definition: playerc++.h:702
void GetWavData(uint8_t *aData) const
Get Wav data This function copies the wav data into the buffer aImage.
Definition: playerc++.h:276
int GetID() const
get the laser ID, call RequestId first
Definition: playerc++.h:1102
player_audio_mixer_channel_detail_t * details
the tones
Definition: player_interfaces.h:1577
The Graphics2dProxy class is used to draw simple graphics into a rendering device provided by Player ...
Definition: playerc++.h:735
Definition: playerclient.h:99
A line segment, used to construct vector-based maps.
Definition: player.h:287
double GetRangeRes() const
Range resolution of scan (mm)
Definition: playerc++.h:1057
uint32_t GetCount(void) const
Gets the number of words.
Definition: playerc++.h:2475
playerc_blobfinder_blob_t GetBlob(uint32_t aIndex) const
returns a blob
Definition: playerc++.h:438
uint32_t GetCount() const
return the point count
Definition: playerc++.h:1674
uint32_t GetWidth() const
Image dimensions (pixels)
Definition: playerc++.h:550
player_wsn_node_data_t data_packet
The WSN node's data packet.
Definition: playerc.h:3622
The geometry of a single bumper.
Definition: player_interfaces.h:1929
uint8_t essid[32]
ESSID id.
Definition: playerc.h:3211
Limb device data.
Definition: playerc.h:2131
double GetMapScale() const
Map scale (m/cell)
Definition: playerc++.h:1329
double vel_x
Linear velocity (m/s).
Definition: playerc.h:2794
The DioProxy class is used to read from a dio (digital I/O) device.
Definition: playerc++.h:590
Player mixer channel.
Definition: player_interfaces.h:1516
double GetPitchSpeed() const
Accessor method.
Definition: playerc++.h:2113
uint32_t GetPathDone() const
Have we arrived at the goal?
Definition: playerc++.h:1547
The ActArrayProxy class is used to control a actarray device.
Definition: playerc++.h:141
uint32_t state
current driver state
Definition: playerc.h:1098
uint8_t * data
raw data
Definition: player_interfaces.h:1471
Player mixer channels.
Definition: player_interfaces.h:1533
enum player_graphics3d_draw_mode player_graphics3d_draw_mode_t
Drawmode: enumeration that defines the drawing mode.
uint32_t GetWidth() const
Map size, in cells.
Definition: playerc++.h:1452
int stall
Stall flag [0, 1].
Definition: playerc.h:2605
player_bbox3d_t GetSize() const
Accessor for the size (fill it in by calling RequestGeom)
Definition: playerc++.h:1735
int status
Status bitfield of extra data in the following order:
Definition: playerc.h:2618
Hypothesis format.
Definition: player_interfaces.h:2333
double GetMaxAngle() const
Scan range for the latest set of data (radians)
Definition: playerc++.h:1065
#define PLAYER_POSITION1D_STATUS_LIMIT_CEN
Status byte: limit center.
Definition: player_interfaces.h:3493
player_orientation_3d_t base_orientation
The orientation of the base of the actarray.
Definition: playerc.h:1003
Actarray device data.
Definition: playerc.h:986