playerc.h
1/*
2 * libplayerc : a Player client library
3 * Copyright (C) Andrew Howard and contributors 2002-2007
4 *
5 * This program is free software; you can redistribute it and/or
6 * modify it under the terms of the GNU General Public License
7 * as published by the Free Software Foundation; either version 2
8 * of the License, or (at your option) any later version.
9 *
10 * This program is distributed in the hope that it will be useful,
11 * but WITHOUT ANY WARRANTY; without even the implied warranty of
12 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13 * GNU General Public License for more details.
14 *
15 * You should have received a copy of the GNU General Public License
16 * along with this program; if not, write to the Free Software
17 * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
18 *
19 */
20
21/***************************************************************************
22 * Desc: Player client
23 * Author: Andrew Howard
24 * Date: 24 Aug 2001
25 # CVS: $Id$
26 **************************************************************************/
27
28
51#ifndef PLAYERC_H
52#define PLAYERC_H
53
54#if !defined (WIN32)
55 #include <netinet/in.h> /* need this for struct sockaddr_in */
56#endif
57#include <stddef.h> /* size_t */
58#include <stdio.h>
59
60#include <playerconfig.h>
61
62/* Get the message structures from Player*/
63#include <libplayercommon/playercommon.h>
64#include <libplayerinterface/player.h>
65#include <libplayercommon/playercommon.h>
66#include <libplayerinterface/interface_util.h>
67#include <libplayerinterface/playerxdr.h>
68#include <libplayerinterface/functiontable.h>
69#include <libplayerwkb/playerwkb.h>
70#if defined (WIN32)
71 #include <winsock2.h>
72#endif
73
74#ifndef MIN
75 #define MIN(a,b) ((a < b) ? a : b)
76#endif
77#ifndef MAX
78 #define MAX(a,b) ((a > b) ? a : b)
79#endif
80
81#if defined (WIN32)
82 #if defined (PLAYER_STATIC)
83 #define PLAYERC_EXPORT
84 #elif defined (playerc_EXPORTS)
85 #define PLAYERC_EXPORT __declspec (dllexport)
86 #else
87 #define PLAYERC_EXPORT __declspec (dllimport)
88 #endif
89#else
90 #define PLAYERC_EXPORT
91#endif
92
93
94#ifdef __cplusplus
95extern "C" {
96#endif
97
98
99/***************************************************************************
100 * Useful constants (re-defined here so SWIG can pick them up easily)
101 **************************************************************************/
102
104#define PLAYERC_OPEN_MODE PLAYER_OPEN_MODE
105#define PLAYERC_CLOSE_MODE PLAYER_CLOSE_MODE
106#define PLAYERC_ERROR_MODE PLAYER_ERROR_MODE
107
108
110#define PLAYERC_DATAMODE_PUSH PLAYER_DATAMODE_PUSH
111#define PLAYERC_DATAMODE_PULL PLAYER_DATAMODE_PULL
112
114#define PLAYERC_TRANSPORT_TCP 1
115#define PLAYERC_TRANSPORT_UDP 2
116
117#define PLAYERC_QUEUE_RING_SIZE 512
118
380/***************************************************************************/
386/***************************************************************************/
387
392PLAYERC_EXPORT const char *playerc_error_str(void);
393
395/*const char *playerc_lookup_name(int code);*/
396
398/*int playerc_lookup_code(const char *name);*/
399
401PLAYERC_EXPORT int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace);
402
404/***************************************************************************/
405
406
407/* Forward declare types*/
408struct _playerc_client_t;
409struct _playerc_device_t;
410struct playerc_blackboard;
411
412
413/* forward declaration to avoid including <sys/poll.h>, which may not be
414 available when people are building clients against this lib*/
415struct pollfd;
416
417
418/***************************************************************************/
429/* Items in incoming data queue.*/
430typedef struct
431{
432 player_msghdr_t header;
433 void *data;
435
436
437/* Multi-client data*/
438typedef struct
439{
440 /* List of clients being managed*/
441 int client_count;
442 struct _playerc_client_t *client[128];
443
444 /* Poll info*/
445 struct pollfd* pollfd;
446
447 /* Latest time received from any server*/
448 double time;
449
451
452/* Create a multi-client object*/
453PLAYERC_EXPORT playerc_mclient_t *playerc_mclient_create(void);
454
455/* Destroy a multi-client object*/
456PLAYERC_EXPORT void playerc_mclient_destroy(playerc_mclient_t *mclient);
457
458/* Add a client to the multi-client (private).*/
459PLAYERC_EXPORT int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
460
461/* Test to see if there is pending data.
462 Returns -1 on error, 0 or 1 otherwise.*/
463PLAYERC_EXPORT int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
464
465/* Read incoming data. The timeout is in ms. Set timeout to a
466 negative value to wait indefinitely.*/
467PLAYERC_EXPORT int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
468
470/***************************************************************************/
471
472
473/***************************************************************************/
486PLAYERC_EXPORT typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
487
489PLAYERC_EXPORT typedef void (*playerc_callback_fn_t) (void *data);
490
491
495typedef struct
496{
499
502
504
505
507typedef struct _playerc_client_t
508{
511 void *id;
512
514 char *host;
515 int port;
516 int transport;
517 struct sockaddr_in server;
518
522
527
531
534
535
537 int sock;
538
540 uint8_t mode;
541
545
549
550
554 int devinfo_count;
555
558 int device_count;
559
561 playerc_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE];
562 int qfirst, qlen, qsize;
563
565 char *data;
566 char *read_xdrdata;
567 size_t read_xdrdata_len;
568
569
571 double datatime;
573 double lasttime;
574
575 double request_timeout;
576
578
579
596 const char *host, int port);
597
604
611 unsigned int transport);
612
622
632
640
655PLAYERC_EXPORT int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
656
669
692PLAYERC_EXPORT int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
693
694
698
699
703
707 playerc_callback_fn_t callback, void *data);
708
712 playerc_callback_fn_t callback, void *data);
713
726
729PLAYERC_EXPORT int playerc_client_subscribe(playerc_client_t *client, int code, int index,
730 int access, char *drivername, size_t len);
731
734PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
735
747 struct _playerc_device_t *device, uint8_t reqtype,
748 const void *req_data, void **rep_data);
749
750
751/* @brief Wait for response from server (blocking).
752
753@param client Pointer to client object.
754@param device
755@param index
756@param sequence
757
758@returns Will return data size for ack, -1 for nack and -2 for failure
759
760
761int playerc_client_getresponse(playerc_client_t *client, uint16_t device,
762 uint16_t index, uint16_t sequence, uint8_t * resptype, uint8_t * resp_data, int resp_len);
763*/
764
765
777PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout);
778
791PLAYERC_EXPORT int playerc_client_internal_peek(playerc_client_t *client, int timeout);
792
808
815
822PLAYERC_EXPORT void playerc_client_set_request_timeout(playerc_client_t* client, uint32_t seconds);
823
831
837PLAYERC_EXPORT void playerc_client_set_retry_time(playerc_client_t* client, double time);
838
842 struct _playerc_device_t *device,
843 uint8_t subtype,
844 void *cmd, double* timestamp);
845
846
848/**************************************************************************/
849
850
851/***************************************************************************/
864typedef struct _playerc_device_t
865{
869 void *id;
870
873
876
879
883
885 double datatime;
886
888 double lasttime;
889
893 int fresh;
902
905
908
911 playerc_callback_fn_t callback[4];
912 void *callback_data[4];
913
915
916
918PLAYERC_EXPORT void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
919 int code, int index, playerc_putmsg_fn_t putmsg);
920
922PLAYERC_EXPORT void playerc_device_term(playerc_device_t *device);
923
925PLAYERC_EXPORT int playerc_device_subscribe(playerc_device_t *device, int access);
926
929
931PLAYERC_EXPORT int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype);
932
934PLAYERC_EXPORT int playerc_device_get_boolprop(playerc_device_t *device, char *property, BOOL *value);
935
937PLAYERC_EXPORT int playerc_device_set_boolprop(playerc_device_t *device, char *property, BOOL value);
938
940PLAYERC_EXPORT int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value);
941
943PLAYERC_EXPORT int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value);
944
946PLAYERC_EXPORT int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value);
947
949PLAYERC_EXPORT int playerc_device_set_dblprop(playerc_device_t *device, char *property, double value);
950
952PLAYERC_EXPORT int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value);
953
955PLAYERC_EXPORT int playerc_device_set_strprop(playerc_device_t *device, char *property, char *value);
956
957
959/**************************************************************************/
960
961
962/***************************************************************************/
967/***************************************************************************/
968
969/**************************************************************************/
979typedef struct
980{
983
984 /* The number of valid analog inputs.*/
985 uint8_t voltages_count;
986
987 /* A bitfield of the current digital inputs.*/
988 float *voltages;
989
991
992
994PLAYERC_EXPORT playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
995
997PLAYERC_EXPORT void playerc_aio_destroy(playerc_aio_t *device);
998
1000PLAYERC_EXPORT int playerc_aio_subscribe(playerc_aio_t *device, int access);
1001
1003PLAYERC_EXPORT int playerc_aio_unsubscribe(playerc_aio_t *device);
1004
1006PLAYERC_EXPORT int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
1007
1009PLAYERC_EXPORT float playerc_aio_get_data(playerc_aio_t *device, uint32_t index);
1010
1012/***************************************************************************/
1013
1014
1015/***************************************************************************/
1026#define PLAYERC_ACTARRAY_NUM_ACTUATORS PLAYER_ACTARRAY_NUM_ACTUATORS
1027#define PLAYERC_ACTARRAY_ACTSTATE_IDLE PLAYER_ACTARRAY_ACTSTATE_IDLE
1028#define PLAYERC_ACTARRAY_ACTSTATE_MOVING PLAYER_ACTARRAY_ACTSTATE_MOVING
1029#define PLAYERC_ACTARRAY_ACTSTATE_BRAKED PLAYER_ACTARRAY_ACTSTATE_BRAKED
1030#define PLAYERC_ACTARRAY_ACTSTATE_STALLED PLAYER_ACTARRAY_ACTSTATE_STALLED
1031#define PLAYERC_ACTARRAY_TYPE_LINEAR PLAYER_ACTARRAY_TYPE_LINEAR
1032#define PLAYERC_ACTARRAY_TYPE_ROTARY PLAYER_ACTARRAY_TYPE_ROTARY
1033
1034
1036typedef struct
1037{
1040
1044 player_actarray_actuator_t *actuators_data;
1047 player_actarray_actuatorgeom_t *actuators_geom;
1055
1058
1061
1063PLAYERC_EXPORT int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
1064
1067
1069PLAYERC_EXPORT player_actarray_actuator_t playerc_actarray_get_actuator_data(playerc_actarray_t *device, uint32_t index);
1070
1072PLAYERC_EXPORT player_actarray_actuatorgeom_t playerc_actarray_get_actuator_geom(playerc_actarray_t *device, uint32_t index);
1073
1077
1079PLAYERC_EXPORT int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
1080
1082PLAYERC_EXPORT int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float *positions, int positions_count);
1083
1085PLAYERC_EXPORT int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
1086
1088PLAYERC_EXPORT int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float *speeds, int speeds_count);
1089
1091PLAYERC_EXPORT int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
1092
1094PLAYERC_EXPORT int playerc_actarray_current_cmd(playerc_actarray_t *device, int joint, float current);
1095
1097PLAYERC_EXPORT int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float *currents, int currents_count);
1098
1099
1103PLAYERC_EXPORT int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
1104
1106PLAYERC_EXPORT int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
1107
1109PLAYERC_EXPORT int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
1110
1111/* Set the accelration of a joint (-1 for all joints) for all subsequent movement commands*/
1112PLAYERC_EXPORT int playerc_actarray_accel_config(playerc_actarray_t *device, int joint, float accel);
1113
1114
1116/**************************************************************************/
1117
1118/***************************************************************************/
1130typedef struct
1131{
1134
1136 player_audio_mixer_channel_list_detail_t channel_details_list;
1137
1139 player_audio_wav_t wav_data;
1140
1142 player_audio_seq_t seq_data;
1143
1145 player_audio_mixer_channel_list_t mixer_data;
1146
1148 uint32_t state;
1149
1150 int last_index;
1151
1153
1155PLAYERC_EXPORT playerc_audio_t *playerc_audio_create(playerc_client_t *client, int index);
1156
1158PLAYERC_EXPORT void playerc_audio_destroy(playerc_audio_t *device);
1159
1161PLAYERC_EXPORT int playerc_audio_subscribe(playerc_audio_t *device, int access);
1162
1164PLAYERC_EXPORT int playerc_audio_unsubscribe(playerc_audio_t *device);
1165
1167PLAYERC_EXPORT int playerc_audio_wav_play_cmd(playerc_audio_t *device, uint32_t data_count, uint8_t data[], uint32_t format);
1168
1170PLAYERC_EXPORT int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state);
1171
1173PLAYERC_EXPORT int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index);
1174
1176PLAYERC_EXPORT int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t * tones);
1177
1179PLAYERC_EXPORT int playerc_audio_mixer_multchannels_cmd(playerc_audio_t *device, player_audio_mixer_channel_list_t * levels);
1180
1182PLAYERC_EXPORT int playerc_audio_mixer_channel_cmd(playerc_audio_t *device, uint32_t index, float amplitude, uint8_t active);
1183
1186PLAYERC_EXPORT int playerc_audio_wav_rec(playerc_audio_t *device);
1187
1189PLAYERC_EXPORT int playerc_audio_sample_load(playerc_audio_t *device, int index, uint32_t data_count, uint8_t data[], uint32_t format);
1190
1193PLAYERC_EXPORT int playerc_audio_sample_retrieve(playerc_audio_t *device, int index);
1194
1196PLAYERC_EXPORT int playerc_audio_sample_rec(playerc_audio_t *device, int index, uint32_t length);
1197
1201
1205
1207/**************************************************************************/
1208
1218#define PLAYERC_BLACKBOARD_DATA_TYPE_NONE 0
1219#define PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE 1
1220#define PLAYERC_BLACKBOARD_DATA_TYPE_COMPLEX 2
1221
1222#define PLAYERC_BLACKBOARD_DATA_SUBTYPE_NONE 0
1223#define PLAYERC_BLACKBOARD_DATA_SUBTYPE_STRING 1
1224#define PLAYERC_BLACKBOARD_DATA_SUBTYPE_INT 2
1225#define PLAYERC_BLACKBOARD_DATA_SUBTYPE_DOUBLE 3
1226
1237
1240
1243
1245PLAYERC_EXPORT int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access);
1246
1249
1252PLAYERC_EXPORT int playerc_blackboard_subscribe_to_key(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1253
1256PLAYERC_EXPORT int playerc_blackboard_get_entry(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1257
1259PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char* key, const char* group);
1260
1262PLAYERC_EXPORT int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char* group);
1263
1265PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char* group);
1266
1269
1270PLAYERC_EXPORT int playerc_blackboard_set_string(playerc_blackboard_t *device, const char* key, const char* group, const char* value);
1271
1272PLAYERC_EXPORT int playerc_blackboard_set_int(playerc_blackboard_t *device, const char* key, const char* group, const int value);
1273
1274PLAYERC_EXPORT int playerc_blackboard_set_double(playerc_blackboard_t *device, const char* key, const char* group, const double value);
1275
1278/**************************************************************************/
1289typedef struct
1290{
1293
1294 uint32_t enabled;
1295 double duty_cycle;
1296 double period;
1297 uint8_t red, green, blue;
1299
1300
1303
1306
1308PLAYERC_EXPORT int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access);
1309
1312
1315 uint32_t enable );
1316
1319 uint32_t id,
1320 uint8_t red,
1321 uint8_t green,
1322 uint8_t blue );
1326 uint32_t id,
1327 float period,
1328 float duty_cycle );
1331/***************************************************************************/
1342typedef player_blobfinder_blob_t playerc_blobfinder_blob_t;
1343
1345typedef struct
1346{
1349
1351 unsigned int width, height;
1352
1354 unsigned int blobs_count;
1355 playerc_blobfinder_blob_t *blobs;
1356
1358
1359
1362
1365
1367PLAYERC_EXPORT int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
1368
1371
1372
1374/**************************************************************************/
1375
1376
1377/**************************************************************************/
1388typedef struct
1389{
1392
1395
1399 player_bumper_define_t *poses;
1400
1403
1405 uint8_t *bumpers;
1406
1408
1409
1411PLAYERC_EXPORT playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
1412
1414PLAYERC_EXPORT void playerc_bumper_destroy(playerc_bumper_t *device);
1415
1417PLAYERC_EXPORT int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
1418
1421
1428PLAYERC_EXPORT int playerc_bumper_get_geom(playerc_bumper_t *device);
1429
1430
1432/***************************************************************************/
1433
1434
1435/***************************************************************************/
1445typedef struct
1446{
1449
1451 int width, height;
1452
1454 int bpp;
1455
1458
1462 int fdiv;
1463
1466
1469
1474 uint8_t *image;
1475
1477 char norm[16];
1478 int source;
1479
1481
1482
1484PLAYERC_EXPORT playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
1485
1487PLAYERC_EXPORT void playerc_camera_destroy(playerc_camera_t *device);
1488
1490PLAYERC_EXPORT int playerc_camera_subscribe(playerc_camera_t *device, int access);
1491
1494
1496PLAYERC_EXPORT void playerc_camera_decompress(playerc_camera_t *device);
1497
1499PLAYERC_EXPORT void playerc_camera_save(playerc_camera_t *device, const char *filename);
1500
1502PLAYERC_EXPORT int playerc_camera_set_source(playerc_camera_t *device, int source, const char *norm);
1503
1506
1508PLAYERC_EXPORT int playerc_camera_get_image(playerc_camera_t *device);
1509
1511PLAYERC_EXPORT void playerc_camera_copy_image(playerc_camera_t * device, void * dst, size_t dst_size);
1512
1514PLAYERC_EXPORT unsigned playerc_camera_get_pixel_component(playerc_camera_t * device, unsigned int x, unsigned int y, int component);
1515
1517/**************************************************************************/
1518
1519/**************************************************************************/
1532typedef struct
1533{
1536
1539
1545 uint8_t origin;
1547 uint16_t id;
1549 uint16_t parent_id;
1550
1554 uint16_t RSSIsender;
1555 uint16_t RSSIvalue;
1556 uint16_t RSSIstamp;
1557 uint32_t RSSInodeTimeHigh;
1558 uint32_t RSSInodeTimeLow;
1559
1561 float x;
1562 float y;
1563 float z;
1564
1565 uint8_t status;
1566
1570 player_coopobject_sensor_t *sensor_data;
1574 player_coopobject_sensor_t *alarm_data;
1575
1579 uint8_t *user_data;
1580
1582 uint8_t command;
1584 uint8_t request;
1588 uint8_t *parameters;
1589
1591
1592
1595
1598
1600PLAYERC_EXPORT int playerc_coopobject_subscribe(playerc_coopobject_t *device, int access);
1601
1604
1606PLAYERC_EXPORT int playerc_coopobject_send_position(playerc_coopobject_t *device, uint16_t node_id, uint16_t source_id, player_pose2d_t pos, uint8_t status);
1607
1609PLAYERC_EXPORT int playerc_coopobject_send_data(playerc_coopobject_t *device, int node_id, int source_id, int data_type, int data_size, unsigned char *extradata);
1610
1612PLAYERC_EXPORT int playerc_coopobject_send_cmd(playerc_coopobject_t *device, int node_id, int source_id, int cmd, int parameters_size, unsigned char *parameters);
1613
1615PLAYERC_EXPORT int playerc_coopobject_send_req(playerc_coopobject_t *device, int node_id, int source_id, int req, int parameters_size, unsigned char *parameters);
1616
1617// /** Put the node in sleep mode (0) or wake it up (1). */
1618//PLAYERC_EXPORT int playerc_coopobject_power(playerc_coopobject_t *device, int node_id, int group_id, int value);
1619
1620// /** Change the data type to RAW or converted engineering units. */
1621//PLAYERC_EXPORT int playerc_coopobject_datatype(playerc_coopobject_t *device, int value);
1622
1623// /** Change data delivery frequency. */
1624//PLAYERC_EXPORT int playerc_coopobject_datafreq(playerc_coopobject_t *device, int node_id, int group_id, double frequency);
1625
1627/***************************************************************************/
1628
1629/**************************************************************************/
1639typedef struct
1640{
1643
1644 /*/ The number of valid digital inputs.*/
1645 uint8_t count;
1646
1647 /*/ A bitfield of the current digital inputs.*/
1648 uint32_t digin;
1649
1651
1652
1654PLAYERC_EXPORT playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
1655
1657PLAYERC_EXPORT void playerc_dio_destroy(playerc_dio_t *device);
1658
1660PLAYERC_EXPORT int playerc_dio_subscribe(playerc_dio_t *device, int access);
1661
1663PLAYERC_EXPORT int playerc_dio_unsubscribe(playerc_dio_t *device);
1664
1666PLAYERC_EXPORT int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
1667
1668
1670/***************************************************************************/
1671
1672
1673/***************************************************************************/
1688typedef struct
1689{
1692
1697 player_fiducial_geom_t fiducial_geom;
1698
1701 player_fiducial_item_t *fiducials;
1702
1704
1705
1708
1711
1713PLAYERC_EXPORT int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
1714
1717
1725
1726
1728/**************************************************************************/
1729
1730/***************************************************************************/
1741typedef struct
1742{
1745
1747 double utc_time;
1748
1752 double lat, lon;
1753
1756 double alt;
1757
1759 double speed;
1760
1763 double course;
1764
1766 double utm_e, utm_n;
1767
1769 double hdop;
1770
1772 double vdop;
1773
1775 double err_horz, err_vert;
1776
1779
1782
1784
1785
1787PLAYERC_EXPORT playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
1788
1790PLAYERC_EXPORT void playerc_gps_destroy(playerc_gps_t *device);
1791
1793PLAYERC_EXPORT int playerc_gps_subscribe(playerc_gps_t *device, int access);
1794
1796PLAYERC_EXPORT int playerc_gps_unsubscribe(playerc_gps_t *device);
1797
1798
1800/**************************************************************************/
1801
1802/***************************************************************************/
1821
1822
1825
1828
1830PLAYERC_EXPORT int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
1831
1834
1837 player_color_t col );
1838
1841 player_point_2d_t pts[],
1842 int count );
1843
1846 player_point_2d_t pts[],
1847 int count );
1848
1851 player_point_2d_t pts[],
1852 int count );
1853
1854
1855
1858 player_point_2d_t pts[],
1859 int count,
1860 int filled,
1861 player_color_t fill_color );
1862
1865
1866
1869/***************************************************************************/
1888
1889
1892
1895
1897PLAYERC_EXPORT int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
1898
1901
1904 player_color_t col );
1905
1908 player_graphics3d_draw_mode_t mode,
1909 player_point_3d_t pts[],
1910 int count );
1911
1914
1917 double x, double y, double z );
1918
1919
1922 double a, double x, double y, double z );
1925/***************************************************************************/
1935typedef struct
1936{
1939
1947 player_bbox3d_t outer_size;
1948 player_bbox3d_t inner_size;
1950 uint8_t num_beams;
1952 uint8_t capacity;
1953
1957 uint8_t state;
1959 uint32_t beams;
1961 uint8_t stored;
1963
1966
1968PLAYERC_EXPORT void playerc_gripper_destroy(playerc_gripper_t *device);
1969
1971PLAYERC_EXPORT int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
1972
1975
1978
1981
1984
1987
1990
1993PLAYERC_EXPORT void playerc_gripper_printout(playerc_gripper_t *device, const char* prefix);
1994
2000
2002/**************************************************************************/
2003
2004/***************************************************************************/
2018typedef struct
2019{
2023 player_health_cpu_t cpu_usage;
2025 player_health_memory_t mem;
2027 player_health_memory_t swap;
2029
2030
2032PLAYERC_EXPORT playerc_health_t *playerc_health_create(playerc_client_t *client, int index);
2033
2035PLAYERC_EXPORT void playerc_health_destroy(playerc_health_t *device);
2036
2038PLAYERC_EXPORT int playerc_health_subscribe(playerc_health_t *device, int access);
2039
2042
2043
2045/***************************************************************************/
2046
2047
2048/***************************************************************************/
2059typedef struct
2060{
2063
2064 /* data*/
2065 player_ir_data_t data;
2066
2067 /* config*/
2068 player_ir_pose_t poses;
2069
2070} playerc_ir_t;
2071
2072
2074PLAYERC_EXPORT playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
2075
2077PLAYERC_EXPORT void playerc_ir_destroy(playerc_ir_t *device);
2078
2080PLAYERC_EXPORT int playerc_ir_subscribe(playerc_ir_t *device, int access);
2081
2083PLAYERC_EXPORT int playerc_ir_unsubscribe(playerc_ir_t *device);
2084
2091PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device);
2092
2093
2095/***************************************************************************/
2096
2097
2098/***************************************************************************/
2108typedef struct
2109{
2112 int32_t axes_count;
2113 int32_t pos[8];
2114 uint32_t buttons;
2115 int * axes_max;
2116 int * axes_min;
2117 double * scale_pos;
2118
2119
2121
2122
2125
2128
2130PLAYERC_EXPORT int playerc_joystick_subscribe(playerc_joystick_t *device, int access);
2131
2134
2136/**************************************************************************/
2137
2138
2139/***************************************************************************/
2153typedef struct
2154{
2157
2161 double pose[3];
2162 double size[2];
2163
2165 double robot_pose[3];
2166
2169
2172
2175
2177 double scan_res;
2178
2181
2184
2187
2189 double *ranges;
2190
2192 double (*scan)[2];
2193
2196
2201
2204
2207
2212
2216 double min_left;
2218
2219
2221PLAYERC_EXPORT playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
2222
2224PLAYERC_EXPORT void playerc_laser_destroy(playerc_laser_t *device);
2225
2227PLAYERC_EXPORT int playerc_laser_subscribe(playerc_laser_t *device, int access);
2228
2230PLAYERC_EXPORT int playerc_laser_unsubscribe(playerc_laser_t *device);
2231
2255 double min_angle, double max_angle,
2256 double resolution,
2257 double range_res,
2258 unsigned char intensity,
2259 double scanning_frequency);
2260
2284 double *min_angle,
2285 double *max_angle,
2286 double *resolution,
2287 double *range_res,
2288 unsigned char *intensity,
2289 double *scanning_frequency);
2290
2297PLAYERC_EXPORT int playerc_laser_get_geom(playerc_laser_t *device);
2298
2303PLAYERC_EXPORT int playerc_laser_get_id (playerc_laser_t *device);
2304
2307PLAYERC_EXPORT void playerc_laser_printout( playerc_laser_t * device,
2308 const char* prefix );
2309
2311/**************************************************************************/
2312
2313
2325typedef struct
2326{
2329
2330 player_limb_data_t data;
2331 player_limb_geom_req_t geom;
2333
2335PLAYERC_EXPORT playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
2336
2338PLAYERC_EXPORT void playerc_limb_destroy(playerc_limb_t *device);
2339
2341PLAYERC_EXPORT int playerc_limb_subscribe(playerc_limb_t *device, int access);
2342
2344PLAYERC_EXPORT int playerc_limb_unsubscribe(playerc_limb_t *device);
2345
2348PLAYERC_EXPORT int playerc_limb_get_geom(playerc_limb_t *device);
2349
2351PLAYERC_EXPORT int playerc_limb_home_cmd(playerc_limb_t *device);
2352
2354PLAYERC_EXPORT int playerc_limb_stop_cmd(playerc_limb_t *device);
2355
2357PLAYERC_EXPORT int playerc_limb_setpose_cmd(playerc_limb_t *device, float pX, float pY, float pZ, float aX, float aY, float aZ, float oX, float oY, float oZ);
2358
2361PLAYERC_EXPORT int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
2362
2365PLAYERC_EXPORT int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
2366
2370PLAYERC_EXPORT int playerc_limb_power(playerc_limb_t *device, uint32_t enable);
2371
2373PLAYERC_EXPORT int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable);
2374
2376PLAYERC_EXPORT int playerc_limb_speed_config(playerc_limb_t *device, float speed);
2377
2379/**************************************************************************/
2380
2381
2382/***************************************************************************/
2400{
2401 double pose[3];
2402 double weight;
2404
2405
2407typedef struct
2408{
2411
2413 int map_size_x, map_size_y;
2414
2417
2419 int map_tile_x, map_tile_y;
2420
2422 int8_t *map_cells;
2423
2426
2429
2432 player_localize_hypoth_t *hypoths;
2433
2434 double mean[3];
2435 double variance;
2436 int num_particles;
2437 playerc_localize_particle_t *particles;
2438
2440
2441
2444
2447
2449PLAYERC_EXPORT int playerc_localize_subscribe(playerc_localize_t *device, int access);
2450
2453
2455PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[6]);
2456
2460
2462/**************************************************************************/
2463
2464
2465/***************************************************************************/
2475typedef struct
2476{
2479
2482 int type;
2483
2488
2489
2491PLAYERC_EXPORT playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
2492
2494PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device);
2495
2497PLAYERC_EXPORT int playerc_log_subscribe(playerc_log_t *device, int access);
2498
2500PLAYERC_EXPORT int playerc_log_unsubscribe(playerc_log_t *device);
2501
2503PLAYERC_EXPORT int playerc_log_set_write_state(playerc_log_t* device, int state);
2504
2506PLAYERC_EXPORT int playerc_log_set_read_state(playerc_log_t* device, int state);
2507
2509PLAYERC_EXPORT int playerc_log_set_read_rewind(playerc_log_t* device);
2510
2516PLAYERC_EXPORT int playerc_log_get_state(playerc_log_t* device);
2517
2519PLAYERC_EXPORT int playerc_log_set_filename(playerc_log_t* device, const char* fname);
2520
2521
2525/***************************************************************************/
2535typedef struct
2536{
2539
2542
2544 int width, height;
2545
2547 double origin[2];
2548
2551
2553 char* cells;
2554
2557 double vminx, vminy, vmaxx, vmaxy;
2558 int num_segments;
2559 player_segment_t* segments;
2561
2564#define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
2565
2567PLAYERC_EXPORT playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
2568
2570PLAYERC_EXPORT void playerc_map_destroy(playerc_map_t *device);
2571
2573PLAYERC_EXPORT int playerc_map_subscribe(playerc_map_t *device, int access);
2574
2576PLAYERC_EXPORT int playerc_map_unsubscribe(playerc_map_t *device);
2577
2579PLAYERC_EXPORT int playerc_map_get_map(playerc_map_t* device);
2580
2582PLAYERC_EXPORT int playerc_map_get_vector(playerc_map_t* device);
2583
2585/**************************************************************************/
2586
2595typedef struct
2596{
2600 uint32_t srid;
2606 player_vectormap_layer_data_t** layers_data;
2608 player_vectormap_layer_info_t** layers_info;
2610 playerwkbprocessor_t wkbprocessor;
2611
2613
2616
2619
2621PLAYERC_EXPORT int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access);
2622
2625
2628
2630PLAYERC_EXPORT int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index);
2631
2633PLAYERC_EXPORT int playerc_vectormap_write_layer(playerc_vectormap_t *device, const player_vectormap_layer_data_t * data);
2634
2637
2640PLAYERC_EXPORT uint8_t * playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2641PLAYERC_EXPORT size_t playerc_vectormap_get_feature_data_count(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2642
2645/***************************************************************************/
2656typedef struct
2657{
2660
2663
2665 uint8_t *data;
2667
2669PLAYERC_EXPORT playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
2670
2672PLAYERC_EXPORT void playerc_opaque_destroy(playerc_opaque_t *device);
2673
2675PLAYERC_EXPORT int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
2676
2679
2681PLAYERC_EXPORT int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
2682
2689PLAYERC_EXPORT int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply);
2690
2692/**************************************************************************/
2693
2694
2695/***************************************************************************/
2705typedef struct
2706{
2709
2712
2715
2717 double px, py, pa;
2718
2720 double gx, gy, ga;
2721
2723 double wx, wy, wa;
2724
2729
2732
2735 double (*waypoints)[3];
2736
2740
2742
2745
2747PLAYERC_EXPORT void playerc_planner_destroy(playerc_planner_t *device);
2748
2750PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access);
2751
2754
2757 double gx, double gy, double ga);
2758
2761 double sx, double sy, double sa);
2762
2770
2776PLAYERC_EXPORT int playerc_planner_enable(playerc_planner_t *device, int state);
2777
2779/**************************************************************************/
2780
2781/***************************************************************************/
2792typedef struct
2793{
2796
2800 double pose[3];
2801 double size[2];
2802
2804 double pos;
2805
2807 double vel;
2808
2811
2824
2826
2829 int index);
2830
2833
2835PLAYERC_EXPORT int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
2836
2839
2841PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable);
2842
2846
2849 double vel, int state);
2850
2855 double pos, int state);
2856
2862 double pos, double vel, int state);
2863
2866 double odom);
2867
2869/**************************************************************************/
2870
2871
2872/***************************************************************************/
2886typedef struct
2887{
2890
2894 double pose[3];
2895 double size[2];
2896
2898 double px, py, pa;
2899
2901 double vx, vy, va;
2902
2905
2907
2910 int index);
2911
2914
2916PLAYERC_EXPORT int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
2917
2920
2922PLAYERC_EXPORT int playerc_position2d_enable(playerc_position2d_t *device, int enable);
2923
2927
2933 double vx, double vy, double va, int state);
2934
2937 player_pose2d_t pos,
2938 player_pose2d_t vel,
2939 int state);
2940
2946 double vx, double vy, double pa, int state);
2947
2948
2949
2953 double gx, double gy, double ga, int state);
2954
2957 double vx, double a);
2958
2961 double ox, double oy, double oa);
2962
2964/**************************************************************************/
2965
2966/***************************************************************************/
2981typedef struct
2982{
2985
2989 double pose[3];
2990 double size[2];
2991
2993 double pos_x, pos_y, pos_z;
2994
2996 double pos_roll, pos_pitch, pos_yaw;
2997
2999 double vel_x, vel_y, vel_z;
3000
3002 double vel_roll, vel_pitch, vel_yaw;
3003
3006
3008
3009
3012 int index);
3013
3016
3018PLAYERC_EXPORT int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
3019
3022
3024PLAYERC_EXPORT int playerc_position3d_enable(playerc_position3d_t *device, int enable);
3025
3029
3035 double vx, double vy, double vz,
3036 double vr, double vp, double vt,
3037 int state);
3038
3041 double vx, double vy, double vz, int state);
3042
3046 double gx, double gy, double gz,
3047 double gr, double gp, double gt);
3048
3049
3052 player_pose3d_t pos,
3053 player_pose3d_t vel);
3054
3057 double gx, double gy, double gz);
3058
3060PLAYERC_EXPORT int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
3061
3064 double ox, double oy, double oz,
3065 double oroll, double opitch, double oyaw);
3066
3069
3071/**************************************************************************/
3072
3073
3074/***************************************************************************/
3085typedef struct
3086{
3089
3093
3095 double charge;
3096
3098 double percent;
3099
3101 double joules;
3102
3105 double watts;
3106
3109
3111
3112
3114PLAYERC_EXPORT playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
3115
3117PLAYERC_EXPORT void playerc_power_destroy(playerc_power_t *device);
3118
3120PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access);
3121
3123PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device);
3124
3125
3127/**************************************************************************/
3128
3129
3130
3131/***************************************************************************/
3142typedef struct
3143{
3146
3150 double pan, tilt;
3151
3153 double zoom;
3154
3158
3159
3161PLAYERC_EXPORT playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
3162
3164PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device);
3165
3167PLAYERC_EXPORT int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
3168
3170PLAYERC_EXPORT int playerc_ptz_unsubscribe(playerc_ptz_t *device);
3171
3180PLAYERC_EXPORT int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
3181
3187PLAYERC_EXPORT int playerc_ptz_query_status(playerc_ptz_t *device);
3188
3199PLAYERC_EXPORT int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
3200 double panspeed, double tiltspeed);
3201
3209PLAYERC_EXPORT int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
3210
3212/**************************************************************************/
3213
3214/***************************************************************************/
3224typedef struct
3225{
3228
3231
3247
3252 player_bbox3d_t device_size;
3257 player_bbox3d_t *element_sizes;
3258
3262 double *ranges;
3263
3270
3275 double *bearings;
3276
3281
3283
3285PLAYERC_EXPORT playerc_ranger_t *playerc_ranger_create(playerc_client_t *client, int index);
3286
3288PLAYERC_EXPORT void playerc_ranger_destroy(playerc_ranger_t *device);
3289
3291PLAYERC_EXPORT int playerc_ranger_subscribe(playerc_ranger_t *device, int access);
3292
3295
3300PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device);
3301
3306PLAYERC_EXPORT int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value);
3307
3312PLAYERC_EXPORT int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value);
3313
3324PLAYERC_EXPORT int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle,
3325 double max_angle, double angular_res,
3326 double min_range, double max_range,
3327 double range_res, double frequency);
3328
3339PLAYERC_EXPORT int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle,
3340 double *max_angle, double *angular_res,
3341 double *min_range, double *max_range,
3342 double *range_res, double *frequency);
3343
3345/**************************************************************************/
3346
3347/***************************************************************************/
3358typedef struct
3359{
3362
3365
3369
3372
3374 double *scan;
3375
3377
3378
3380PLAYERC_EXPORT playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
3381
3383PLAYERC_EXPORT void playerc_sonar_destroy(playerc_sonar_t *device);
3384
3386PLAYERC_EXPORT int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
3387
3389PLAYERC_EXPORT int playerc_sonar_unsubscribe(playerc_sonar_t *device);
3390
3396PLAYERC_EXPORT int playerc_sonar_get_geom(playerc_sonar_t *device);
3397
3399/**************************************************************************/
3400
3401/***************************************************************************/
3413typedef struct
3414{
3416 uint8_t mac[32];
3417
3419 uint8_t ip[32];
3420
3422 uint8_t essid[32];
3423
3425 int mode;
3426
3429
3431 double freq;
3432
3434 int qual, level, noise;
3435
3437
3438
3440typedef struct
3441{
3444
3447 int link_count;
3448 char ip[32];
3450
3451
3453PLAYERC_EXPORT playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
3454
3456PLAYERC_EXPORT void playerc_wifi_destroy(playerc_wifi_t *device);
3457
3459PLAYERC_EXPORT int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
3460
3462PLAYERC_EXPORT int playerc_wifi_unsubscribe(playerc_wifi_t *device);
3463
3466
3467
3469/**************************************************************************/
3470
3471/***************************************************************************/
3483typedef struct
3484{
3487
3489
3490
3493
3496
3498PLAYERC_EXPORT int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
3499
3502
3504PLAYERC_EXPORT int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
3505 double gx, double gy, double ga);
3506
3508PLAYERC_EXPORT int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
3509 double *x, double *y, double *a);
3510
3512PLAYERC_EXPORT int playerc_simulation_set_pose3d(playerc_simulation_t *device, char* name,
3513 double gx, double gy, double gz,
3514 double groll, double gpitch, double gyaw);
3515
3517PLAYERC_EXPORT int playerc_simulation_get_pose3d(playerc_simulation_t *device, char* identifier,
3518 double *x, double *y, double *z,
3519 double *roll, double *pitch, double *yaw, double *time);
3520
3523 char* name,
3524 char* property,
3525 void* value,
3526 size_t value_len);
3527
3530 char* name,
3531 char* property,
3532 void* value,
3533 size_t value_len);
3534
3537
3540
3543
3544
3546/***************************************************************************/
3547
3548
3549/**************************************************************************/
3559typedef struct
3560{
3564
3565
3567PLAYERC_EXPORT playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
3568
3570PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device);
3571
3573PLAYERC_EXPORT int playerc_speech_subscribe(playerc_speech_t *device, int access);
3574
3577
3579PLAYERC_EXPORT int playerc_speech_say (playerc_speech_t *device, char *);
3580
3581
3583/***************************************************************************/
3584
3585/**************************************************************************/
3595typedef struct
3596{
3599
3600 char *rawText;
3601 /* Just estimating that no more than 20 words will be spoken between updates.
3602 Assuming that the longest word is <= 30 characters.*/
3603 char **words;
3604 int wordCount;
3606
3607
3610
3613
3616
3619
3621/***************************************************************************/
3622
3623/**************************************************************************/
3633typedef struct
3634{
3636 uint32_t type;
3638 uint32_t guid_count;
3640 uint8_t *guid;
3642
3644typedef struct
3645{
3648
3650 uint16_t tags_count;
3651
3655
3656
3658PLAYERC_EXPORT playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
3659
3661PLAYERC_EXPORT void playerc_rfid_destroy(playerc_rfid_t *device);
3662
3664PLAYERC_EXPORT int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
3665
3667PLAYERC_EXPORT int playerc_rfid_unsubscribe(playerc_rfid_t *device);
3668
3670/***************************************************************************/
3671
3672/**************************************************************************/
3682typedef player_pointcloud3d_element_t playerc_pointcloud3d_element_t;
3683
3696
3697
3700
3703
3705PLAYERC_EXPORT int playerc_pointcloud3d_subscribe (playerc_pointcloud3d_t *device, int access);
3706
3709
3711/***************************************************************************/
3712
3713/**************************************************************************/
3722typedef player_pointcloud3d_stereo_element_t playerc_pointcloud3d_stereo_element_t;
3723
3725typedef struct
3726{
3729
3730 /* Left channel image */
3731 playerc_camera_t left_channel;
3732 /* Right channel image */
3733 playerc_camera_t right_channel;
3734
3735 /* Disparity image */
3736 playerc_camera_t disparity;
3737
3738 /* 3-D stereo point cloud */
3739 uint32_t points_count;
3741// player_pointcloud3d_data_t pointcloud;
3743
3744
3746PLAYERC_EXPORT playerc_stereo_t *playerc_stereo_create (playerc_client_t *client, int index);
3747
3749PLAYERC_EXPORT void playerc_stereo_destroy (playerc_stereo_t *device);
3750
3752PLAYERC_EXPORT int playerc_stereo_subscribe (playerc_stereo_t *device, int access);
3753
3756
3758/***************************************************************************/
3759
3760/**************************************************************************/
3770typedef struct
3771{
3774
3777 player_pose3d_t vel;
3778 player_pose3d_t acc;
3779
3781 player_imu_data_calib_t calib_data;
3782
3784 float q0, q1, q2, q3;
3786
3788PLAYERC_EXPORT playerc_imu_t *playerc_imu_create (playerc_client_t *client, int index);
3789
3791PLAYERC_EXPORT void playerc_imu_destroy (playerc_imu_t *device);
3792
3794PLAYERC_EXPORT int playerc_imu_subscribe (playerc_imu_t *device, int access);
3795
3797PLAYERC_EXPORT int playerc_imu_unsubscribe (playerc_imu_t *device);
3798
3800PLAYERC_EXPORT int playerc_imu_datatype (playerc_imu_t *device, int value);
3801
3803PLAYERC_EXPORT int playerc_imu_reset_orientation (playerc_imu_t *device, int value);
3804
3806PLAYERC_EXPORT int playerc_imu_reset_euler(playerc_imu_t *device, float roll, float pitch, float yaw);
3807
3809/***************************************************************************/
3810
3811/**************************************************************************/
3824typedef struct
3825{
3828
3830 uint32_t node_type;
3832 uint32_t node_id;
3836 player_wsn_node_data_t data_packet;
3838
3839
3841PLAYERC_EXPORT playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
3842
3844PLAYERC_EXPORT void playerc_wsn_destroy(playerc_wsn_t *device);
3845
3847PLAYERC_EXPORT int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
3848
3850PLAYERC_EXPORT int playerc_wsn_unsubscribe(playerc_wsn_t *device);
3851
3853PLAYERC_EXPORT int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
3854 int group_id, int devnr, int state);
3855
3857PLAYERC_EXPORT int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
3858 int value);
3859
3861PLAYERC_EXPORT int playerc_wsn_datatype(playerc_wsn_t *device, int value);
3862
3864PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
3865 double frequency);
3866
3868/***************************************************************************/
3869
3870#ifdef __cplusplus
3871}
3872#endif
3873
3874#endif
#define PLAYER_MAX_DRIVER_STRING_LEN
Maximum length for a driver name.
Definition player.h:72
#define PLAYER_MAX_DEVICES
The maximum number of devices the server will support.
Definition player.h:74
PLAYERC_EXPORT typedef void(* playerc_putmsg_fn_t)(void *device, char *header, char *data)
Typedef for proxy callback function.
Definition playerc.h:486
PLAYERC_EXPORT playerc_client_t * playerc_client_create(playerc_mclient_t *mclient, const char *host, int port)
Create a client object.
struct _playerc_client_t playerc_client_t
Client object data.
PLAYERC_EXPORT int playerc_client_request(playerc_client_t *client, struct _playerc_device_t *device, uint8_t reqtype, const void *req_data, void **rep_data)
Issue a request to the server and await a reply (blocking).
PLAYERC_EXPORT void playerc_client_destroy(playerc_client_t *client)
Destroy a client object.
PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout)
Test to see if there is pending data.
PLAYERC_EXPORT void * playerc_client_read(playerc_client_t *client)
Read data from the server (blocking).
PLAYERC_EXPORT void playerc_client_set_retry_limit(playerc_client_t *client, int limit)
Set the connection retry limit.
PLAYERC_EXPORT int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device, playerc_callback_fn_t callback, void *data)
Add user callbacks (called when new data arrives).
PLAYERC_EXPORT int playerc_client_subscribe(playerc_client_t *client, int code, int index, int access, char *drivername, size_t len)
Subscribe a device.
PLAYERC_EXPORT int playerc_client_connect(playerc_client_t *client)
Connect to the server.
PLAYERC_EXPORT int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace)
Set a replace rule for the client queue on the server.
PLAYERC_EXPORT int playerc_client_disconnect(playerc_client_t *client)
Disconnect from the server.
PLAYERC_EXPORT int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device)
Add a device proxy.
PLAYERC_EXPORT int playerc_client_get_devlist(playerc_client_t *client)
Get the list of available device ids.
PLAYERC_EXPORT int playerc_client_write(playerc_client_t *client, struct _playerc_device_t *device, uint8_t subtype, void *cmd, double *timestamp)
Write data to the server.
PLAYERC_EXPORT void playerc_client_set_transport(playerc_client_t *client, unsigned int transport)
Set the transport type.
PLAYERC_EXPORT int playerc_client_read_nonblock_withproxy(playerc_client_t *client, void **proxy)
Read and process a packet (nonblocking), fills in pointer to proxy that got data.
PLAYERC_EXPORT int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device, playerc_callback_fn_t callback, void *data)
Remove user callbacks (called when new data arrives).
PLAYERC_EXPORT int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device)
Remove a device proxy.
PLAYERC_EXPORT int playerc_client_read_nonblock(playerc_client_t *client)
Read and process a packet (nonblocking)
PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index)
Unsubscribe a device.
PLAYERC_EXPORT int playerc_client_datamode(playerc_client_t *client, uint8_t mode)
Change the server's data delivery mode.
PLAYERC_EXPORT int playerc_client_internal_peek(playerc_client_t *client, int timeout)
Test to see if there is pending data.
PLAYERC_EXPORT void playerc_client_set_request_timeout(playerc_client_t *client, uint32_t seconds)
Set the timeout for client requests.
PLAYERC_EXPORT int playerc_client_requestdata(playerc_client_t *client)
Request a round of data.
PLAYERC_EXPORT typedef void(* playerc_callback_fn_t)(void *data)
Typedef for proxy callback function.
Definition playerc.h:489
PLAYERC_EXPORT void playerc_client_set_retry_time(playerc_client_t *client, double time)
Set the connection retry sleep time.
PLAYERC_EXPORT int playerc_client_disconnect_retry(playerc_client_t *client)
Disconnect from the server, with potential retry.
struct _playerc_device_t playerc_device_t
Common device info.
PLAYERC_EXPORT int playerc_device_set_strprop(playerc_device_t *device, char *property, char *value)
Set a string property.
PLAYERC_EXPORT int playerc_device_unsubscribe(playerc_device_t *device)
Unsubscribe the device.
PLAYERC_EXPORT int playerc_device_get_boolprop(playerc_device_t *device, char *property, BOOL *value)
Request a boolean property.
PLAYERC_EXPORT int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value)
Request an integer property.
PLAYERC_EXPORT int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value)
Request a string property.
PLAYERC_EXPORT int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value)
Set an integer property.
PLAYERC_EXPORT int playerc_device_set_boolprop(playerc_device_t *device, char *property, BOOL value)
Set a boolean property.
PLAYERC_EXPORT void playerc_device_term(playerc_device_t *device)
Finalize the device.
PLAYERC_EXPORT void playerc_device_init(playerc_device_t *device, playerc_client_t *client, int code, int index, playerc_putmsg_fn_t putmsg)
Initialise the device.
PLAYERC_EXPORT int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype)
Request capabilities of device.
PLAYERC_EXPORT int playerc_device_set_dblprop(playerc_device_t *device, char *property, double value)
Set a double property.
PLAYERC_EXPORT int playerc_device_subscribe(playerc_device_t *device, int access)
Subscribe the device.
PLAYERC_EXPORT int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value)
Request a double property.
PLAYERC_EXPORT int playerc_actarray_unsubscribe(playerc_actarray_t *device)
Un-subscribe from the actarray device.
PLAYERC_EXPORT int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position)
Command a joint in the array to move to a specified position.
PLAYERC_EXPORT int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable)
Turn the power to the array on or off.
PLAYERC_EXPORT void playerc_actarray_destroy(playerc_actarray_t *device)
Destroy an actarray proxy.
PLAYERC_EXPORT int playerc_actarray_get_geom(playerc_actarray_t *device)
Get the actarray geometry.
PLAYERC_EXPORT int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable)
Turn the brakes of all actuators in the array that have them on or off.
PLAYERC_EXPORT player_actarray_actuator_t playerc_actarray_get_actuator_data(playerc_actarray_t *device, uint32_t index)
Accessor method for the actuator data.
PLAYERC_EXPORT playerc_actarray_t * playerc_actarray_create(playerc_client_t *client, int index)
Create an actarray proxy.
PLAYERC_EXPORT int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float *currents, int currents_count)
Command all joints in the array to move with specified currents.
PLAYERC_EXPORT player_actarray_actuatorgeom_t playerc_actarray_get_actuator_geom(playerc_actarray_t *device, uint32_t index)
Accessor method for the actuator geom.
PLAYERC_EXPORT int playerc_actarray_current_cmd(playerc_actarray_t *device, int joint, float current)
Command a joint in the array to move with a specified current.
PLAYERC_EXPORT int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed)
Command a joint in the array to move at a specified speed.
PLAYERC_EXPORT int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float *speeds, int speeds_count)
Command a joint in the array to move at a specified speed.
PLAYERC_EXPORT int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float *positions, int positions_count)
Command all joints in the array to move to specified positions.
PLAYERC_EXPORT int playerc_actarray_subscribe(playerc_actarray_t *device, int access)
Subscribe to the actarray device.
PLAYERC_EXPORT int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed)
Set the speed of a joint (-1 for all joints) for all subsequent movement commands.
PLAYERC_EXPORT int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint)
Command a joint (or, if joint is -1, the whole array) to go to its home position.
PLAYERC_EXPORT int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt)
Set the output for the aio device.
PLAYERC_EXPORT float playerc_aio_get_data(playerc_aio_t *device, uint32_t index)
get the aio data
PLAYERC_EXPORT playerc_aio_t * playerc_aio_create(playerc_client_t *client, int index)
Create a aio proxy.
PLAYERC_EXPORT void playerc_aio_destroy(playerc_aio_t *device)
Destroy a aio proxy.
PLAYERC_EXPORT int playerc_aio_unsubscribe(playerc_aio_t *device)
Un-subscribe from the aio device.
PLAYERC_EXPORT int playerc_aio_subscribe(playerc_aio_t *device, int access)
Subscribe to the aio device.
PLAYERC_EXPORT int playerc_audio_mixer_multchannels_cmd(playerc_audio_t *device, player_audio_mixer_channel_list_t *levels)
Command to set mixer levels for multiple channels.
PLAYERC_EXPORT playerc_audio_t * playerc_audio_create(playerc_client_t *client, int index)
Create an audio proxy.
PLAYERC_EXPORT int playerc_audio_wav_rec(playerc_audio_t *device)
Request to record a single audio block Value is returned into wav_data, block length is determined by...
PLAYERC_EXPORT int playerc_audio_subscribe(playerc_audio_t *device, int access)
Subscribe to the audio device.
PLAYERC_EXPORT int playerc_audio_sample_retrieve(playerc_audio_t *device, int index)
Request to retrieve an audio sample Data is stored in wav_data.
PLAYERC_EXPORT int playerc_audio_get_mixer_details(playerc_audio_t *device)
Request mixer channel details list result is stored in channel_details_list.
PLAYERC_EXPORT int playerc_audio_unsubscribe(playerc_audio_t *device)
Un-subscribe from the audio device.
PLAYERC_EXPORT int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state)
Command to set recording state.
PLAYERC_EXPORT int playerc_audio_wav_play_cmd(playerc_audio_t *device, uint32_t data_count, uint8_t data[], uint32_t format)
Command to play an audio block.
PLAYERC_EXPORT int playerc_audio_mixer_channel_cmd(playerc_audio_t *device, uint32_t index, float amplitude, uint8_t active)
Command to set mixer levels for a single channel.
PLAYERC_EXPORT int playerc_audio_get_mixer_levels(playerc_audio_t *device)
Request mixer channel data result is stored in mixer_data.
PLAYERC_EXPORT int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index)
Command to play prestored sample.
PLAYERC_EXPORT int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t *tones)
Command to play sequence of tones.
PLAYERC_EXPORT void playerc_audio_destroy(playerc_audio_t *device)
Destroy an audio proxy.
PLAYERC_EXPORT int playerc_audio_sample_load(playerc_audio_t *device, int index, uint32_t data_count, uint8_t data[], uint32_t format)
Request to load an audio sample.
PLAYERC_EXPORT int playerc_audio_sample_rec(playerc_audio_t *device, int index, uint32_t length)
Request to record new sample.
PLAYERC_EXPORT int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access)
Subscribe to the blackboard device.
PLAYERC_EXPORT int playerc_blackboard_unsubscribe(playerc_blackboard_t *device)
Un-subscribe from the blackboard device.
PLAYERC_EXPORT int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char *group)
Subscribe to a group.
PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char *key, const char *group)
Unsubscribe from a key.
PLAYERC_EXPORT int playerc_blackboard_get_entry(playerc_blackboard_t *device, const char *key, const char *group, player_blackboard_entry_t **entry)
Get the current value of a key, without subscribing.
PLAYERC_EXPORT int playerc_blackboard_subscribe_to_key(playerc_blackboard_t *device, const char *key, const char *group, player_blackboard_entry_t **entry)
Subscribe to a key.
PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char *group)
Unsubscribe from a group.
PLAYERC_EXPORT void playerc_blackboard_destroy(playerc_blackboard_t *device)
Destroy a blackboard proxy.
PLAYERC_EXPORT int playerc_blackboard_set_entry(playerc_blackboard_t *device, player_blackboard_entry_t *entry)
Set an entry value.
struct playerc_blackboard playerc_blackboard_t
BlackBoard proxy.
PLAYERC_EXPORT playerc_blackboard_t * playerc_blackboard_create(playerc_client_t *client, int index)
Create a blackboard proxy.
PLAYERC_EXPORT playerc_blinkenlight_t * playerc_blinkenlight_create(playerc_client_t *client, int index)
Create a blinkenlight proxy.
PLAYERC_EXPORT int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access)
Subscribe to the blinkenlight device.
PLAYERC_EXPORT int playerc_blinkenlight_color(playerc_blinkenlight_t *device, uint32_t id, uint8_t red, uint8_t green, uint8_t blue)
Set the output color for the blinkenlight device.
PLAYERC_EXPORT int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device)
Un-subscribe from the blinkenlight device.
PLAYERC_EXPORT int playerc_blinkenlight_enable(playerc_blinkenlight_t *device, uint32_t enable)
Enable/disable power to the blinkenlight device.
PLAYERC_EXPORT int playerc_blinkenlight_blink(playerc_blinkenlight_t *device, uint32_t id, float period, float duty_cycle)
Make the light blink, setting the period in seconds and the mark/space ratiom (0.0 to 1....
PLAYERC_EXPORT void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device)
Destroy a blinkenlight proxy.
PLAYERC_EXPORT int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device)
Un-subscribe from the blobfinder device.
PLAYERC_EXPORT int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access)
Subscribe to the blobfinder device.
PLAYERC_EXPORT void playerc_blobfinder_destroy(playerc_blobfinder_t *device)
Destroy a blobfinder proxy.
PLAYERC_EXPORT playerc_blobfinder_t * playerc_blobfinder_create(playerc_client_t *client, int index)
Create a blobfinder proxy.
PLAYERC_EXPORT playerc_bumper_t * playerc_bumper_create(playerc_client_t *client, int index)
Create a bumper proxy.
PLAYERC_EXPORT int playerc_bumper_get_geom(playerc_bumper_t *device)
Get the bumper geometry.
PLAYERC_EXPORT int playerc_bumper_subscribe(playerc_bumper_t *device, int access)
Subscribe to the bumper device.
PLAYERC_EXPORT void playerc_bumper_destroy(playerc_bumper_t *device)
Destroy a bumper proxy.
PLAYERC_EXPORT int playerc_bumper_unsubscribe(playerc_bumper_t *device)
Un-subscribe from the bumper device.
PLAYERC_EXPORT void playerc_camera_decompress(playerc_camera_t *device)
Decompress the image (modifies the current proxy data).
PLAYERC_EXPORT int playerc_camera_set_source(playerc_camera_t *device, int source, const char *norm)
Set source channel.
PLAYERC_EXPORT unsigned playerc_camera_get_pixel_component(playerc_camera_t *device, unsigned int x, unsigned int y, int component)
Get given component of given pixel.
PLAYERC_EXPORT void playerc_camera_copy_image(playerc_camera_t *device, void *dst, size_t dst_size)
Copy image to some pre-allocated place.
PLAYERC_EXPORT int playerc_camera_get_source(playerc_camera_t *device)
Get source channel (sets norm and source fields in the current proxy data).
PLAYERC_EXPORT void playerc_camera_save(playerc_camera_t *device, const char *filename)
Saves the image to disk as a .ppm.
PLAYERC_EXPORT int playerc_camera_unsubscribe(playerc_camera_t *device)
Un-subscribe from the camera device.
PLAYERC_EXPORT int playerc_camera_subscribe(playerc_camera_t *device, int access)
Subscribe to the camera device.
PLAYERC_EXPORT playerc_camera_t * playerc_camera_create(playerc_client_t *client, int index)
Create a camera proxy.
PLAYERC_EXPORT void playerc_camera_destroy(playerc_camera_t *device)
Destroy a camera proxy.
PLAYERC_EXPORT int playerc_camera_get_image(playerc_camera_t *device)
Force to get current image.
PLAYERC_EXPORT playerc_coopobject_t * playerc_coopobject_create(playerc_client_t *client, int index)
Create a cooperating object proxy.
PLAYERC_EXPORT int playerc_coopobject_send_position(playerc_coopobject_t *device, uint16_t node_id, uint16_t source_id, player_pose2d_t pos, uint8_t status)
Send data to cooperating object.
PLAYERC_EXPORT int playerc_coopobject_send_cmd(playerc_coopobject_t *device, int node_id, int source_id, int cmd, int parameters_size, unsigned char *parameters)
Send command to cooperating object.
PLAYERC_EXPORT int playerc_coopobject_unsubscribe(playerc_coopobject_t *device)
Un-subscribe from the cooperating object device.
PLAYERC_EXPORT int playerc_coopobject_send_data(playerc_coopobject_t *device, int node_id, int source_id, int data_type, int data_size, unsigned char *extradata)
Send data to cooperating object.
PLAYERC_EXPORT int playerc_coopobject_subscribe(playerc_coopobject_t *device, int access)
Subscribe to the cooperating object device.
PLAYERC_EXPORT int playerc_coopobject_send_req(playerc_coopobject_t *device, int node_id, int source_id, int req, int parameters_size, unsigned char *parameters)
Send request to cooperating object.
PLAYERC_EXPORT void playerc_coopobject_destroy(playerc_coopobject_t *device)
Destroy a cooperating object proxy.
PLAYERC_EXPORT int playerc_dio_unsubscribe(playerc_dio_t *device)
Un-subscribe from the dio device.
PLAYERC_EXPORT int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout)
Set the output for the dio device.
PLAYERC_EXPORT void playerc_dio_destroy(playerc_dio_t *device)
Destroy a dio proxy.
PLAYERC_EXPORT int playerc_dio_subscribe(playerc_dio_t *device, int access)
Subscribe to the dio device.
PLAYERC_EXPORT playerc_dio_t * playerc_dio_create(playerc_client_t *client, int index)
Create a dio proxy.
PLAYERC_EXPORT int playerc_fiducial_get_geom(playerc_fiducial_t *device)
Get the fiducial geometry.
PLAYERC_EXPORT int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access)
Subscribe to the fiducial device.
PLAYERC_EXPORT void playerc_fiducial_destroy(playerc_fiducial_t *device)
Destroy a fiducial proxy.
PLAYERC_EXPORT playerc_fiducial_t * playerc_fiducial_create(playerc_client_t *client, int index)
Create a fiducial proxy.
PLAYERC_EXPORT int playerc_fiducial_unsubscribe(playerc_fiducial_t *device)
Un-subscribe from the fiducial device.
PLAYERC_EXPORT int playerc_gps_unsubscribe(playerc_gps_t *device)
Un-subscribe from the gps device.
PLAYERC_EXPORT int playerc_gps_subscribe(playerc_gps_t *device, int access)
Subscribe to the gps device.
PLAYERC_EXPORT playerc_gps_t * playerc_gps_create(playerc_client_t *client, int index)
Create a gps proxy.
PLAYERC_EXPORT void playerc_gps_destroy(playerc_gps_t *device)
Destroy a gps proxy.
PLAYERC_EXPORT int playerc_graphics2d_draw_points(playerc_graphics2d_t *device, player_point_2d_t pts[], int count)
Draw some points.
PLAYERC_EXPORT int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access)
Subscribe to the graphics2d device.
PLAYERC_EXPORT int playerc_graphics2d_draw_multiline(playerc_graphics2d_t *device, player_point_2d_t pts[], int count)
Draw a set of lines whose end points are at pts[2n] and pts[2n+1].
PLAYERC_EXPORT void playerc_graphics2d_destroy(playerc_graphics2d_t *device)
Destroy a graphics2d device proxy.
PLAYERC_EXPORT int playerc_graphics2d_clear(playerc_graphics2d_t *device)
Clear the canvas.
PLAYERC_EXPORT playerc_graphics2d_t * playerc_graphics2d_create(playerc_client_t *client, int index)
Create a graphics2d device proxy.
PLAYERC_EXPORT int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device, player_point_2d_t pts[], int count, int filled, player_color_t fill_color)
Draw a polygon.
PLAYERC_EXPORT int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device, player_point_2d_t pts[], int count)
Draw a polyline that connects an array of points.
PLAYERC_EXPORT int playerc_graphics2d_setcolor(playerc_graphics2d_t *device, player_color_t col)
Set the current drawing color.
PLAYERC_EXPORT int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device)
Un-subscribe from the graphics2d device.
PLAYERC_EXPORT playerc_graphics3d_t * playerc_graphics3d_create(playerc_client_t *client, int index)
Create a graphics3d device proxy.
PLAYERC_EXPORT void playerc_graphics3d_destroy(playerc_graphics3d_t *device)
Destroy a graphics3d device proxy.
PLAYERC_EXPORT int playerc_graphics3d_setcolor(playerc_graphics3d_t *device, player_color_t col)
Set the current drawing color.
PLAYERC_EXPORT int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device)
Un-subscribe from the graphics3d device.
PLAYERC_EXPORT int playerc_graphics3d_draw(playerc_graphics3d_t *device, player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count)
Draw some points in the given mode.
PLAYERC_EXPORT int playerc_graphics3d_clear(playerc_graphics3d_t *device)
Clear the canvas.
PLAYERC_EXPORT int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access)
Subscribe to the graphics3d device.
PLAYERC_EXPORT int playerc_graphics3d_rotate(playerc_graphics3d_t *device, double a, double x, double y, double z)
Rotate the drawing coordinate system by [a] radians about the vector described by [x,...
PLAYERC_EXPORT int playerc_graphics3d_translate(playerc_graphics3d_t *device, double x, double y, double z)
Translate the drawing coordinate system in 3d.
PLAYERC_EXPORT int playerc_gripper_retrieve_cmd(playerc_gripper_t *device)
Command the gripper to retrieve.
PLAYERC_EXPORT void playerc_gripper_destroy(playerc_gripper_t *device)
Destroy a gripper device proxy.
PLAYERC_EXPORT int playerc_gripper_unsubscribe(playerc_gripper_t *device)
Un-subscribe from the gripper device.
PLAYERC_EXPORT int playerc_gripper_subscribe(playerc_gripper_t *device, int access)
Subscribe to the gripper device.
PLAYERC_EXPORT int playerc_gripper_store_cmd(playerc_gripper_t *device)
Command the gripper to store.
PLAYERC_EXPORT playerc_gripper_t * playerc_gripper_create(playerc_client_t *client, int index)
Create a gripper device proxy.
PLAYERC_EXPORT int playerc_gripper_stop_cmd(playerc_gripper_t *device)
Command the gripper to stop.
PLAYERC_EXPORT void playerc_gripper_printout(playerc_gripper_t *device, const char *prefix)
Print a human-readable version of the gripper state.
PLAYERC_EXPORT int playerc_gripper_open_cmd(playerc_gripper_t *device)
Command the gripper to open.
PLAYERC_EXPORT int playerc_gripper_close_cmd(playerc_gripper_t *device)
Command the gripper to close.
PLAYERC_EXPORT int playerc_gripper_get_geom(playerc_gripper_t *device)
Get the gripper geometry.
PLAYERC_EXPORT int playerc_health_subscribe(playerc_health_t *device, int access)
Subscribe to the health device.
PLAYERC_EXPORT playerc_health_t * playerc_health_create(playerc_client_t *client, int index)
Create a health proxy.
PLAYERC_EXPORT int playerc_health_unsubscribe(playerc_health_t *device)
Un-subscribe from the health device.
PLAYERC_EXPORT void playerc_health_destroy(playerc_health_t *device)
Destroy a health proxy.
PLAYERC_EXPORT int playerc_imu_reset_orientation(playerc_imu_t *device, int value)
Reset orientation.
PLAYERC_EXPORT int playerc_imu_datatype(playerc_imu_t *device, int value)
Change the data type to one of the predefined data structures.
PLAYERC_EXPORT int playerc_imu_reset_euler(playerc_imu_t *device, float roll, float pitch, float yaw)
Reset euler orientation.
PLAYERC_EXPORT int playerc_imu_unsubscribe(playerc_imu_t *device)
Un-subscribe from the imu device.
PLAYERC_EXPORT void playerc_imu_destroy(playerc_imu_t *device)
Destroy a imu proxy.
PLAYERC_EXPORT playerc_imu_t * playerc_imu_create(playerc_client_t *client, int index)
Create a imu proxy.
PLAYERC_EXPORT int playerc_imu_subscribe(playerc_imu_t *device, int access)
Subscribe to the imu device.
PLAYERC_EXPORT void playerc_ir_destroy(playerc_ir_t *device)
Destroy a ir proxy.
PLAYERC_EXPORT playerc_ir_t * playerc_ir_create(playerc_client_t *client, int index)
Create a ir proxy.
PLAYERC_EXPORT int playerc_ir_unsubscribe(playerc_ir_t *device)
Un-subscribe from the ir device.
PLAYERC_EXPORT int playerc_ir_subscribe(playerc_ir_t *device, int access)
Subscribe to the ir device.
PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device)
Get the ir geometry.
PLAYERC_EXPORT void playerc_joystick_destroy(playerc_joystick_t *device)
Destroy a joystick proxy.
PLAYERC_EXPORT int playerc_joystick_unsubscribe(playerc_joystick_t *device)
Un-subscribe from the joystick device.
PLAYERC_EXPORT playerc_joystick_t * playerc_joystick_create(playerc_client_t *client, int index)
Create a joystick proxy.
PLAYERC_EXPORT int playerc_joystick_subscribe(playerc_joystick_t *device, int access)
Subscribe to the joystick device.
PLAYERC_EXPORT int playerc_laser_get_geom(playerc_laser_t *device)
Get the laser geometry.
PLAYERC_EXPORT void playerc_laser_printout(playerc_laser_t *device, const char *prefix)
Print a human-readable summary of the laser state on stdout.
PLAYERC_EXPORT int playerc_laser_get_config(playerc_laser_t *device, double *min_angle, double *max_angle, double *resolution, double *range_res, unsigned char *intensity, double *scanning_frequency)
Get the laser configuration.
PLAYERC_EXPORT playerc_laser_t * playerc_laser_create(playerc_client_t *client, int index)
Create a laser proxy.
PLAYERC_EXPORT int playerc_laser_set_config(playerc_laser_t *device, double min_angle, double max_angle, double resolution, double range_res, unsigned char intensity, double scanning_frequency)
Configure the laser.
PLAYERC_EXPORT int playerc_laser_subscribe(playerc_laser_t *device, int access)
Subscribe to the laser device.
PLAYERC_EXPORT void playerc_laser_destroy(playerc_laser_t *device)
Destroy a laser proxy.
PLAYERC_EXPORT int playerc_laser_unsubscribe(playerc_laser_t *device)
Un-subscribe from the laser device.
PLAYERC_EXPORT int playerc_laser_get_id(playerc_laser_t *device)
Get the laser IDentification information.
PLAYERC_EXPORT int playerc_limb_speed_config(playerc_limb_t *device, float speed)
Set the speed of the end effector (m/s) for all subsequent movement commands.
PLAYERC_EXPORT void playerc_limb_destroy(playerc_limb_t *device)
Destroy a limb proxy.
PLAYERC_EXPORT int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable)
Turn the brakes of all actuators in the limb that have them on or off.
PLAYERC_EXPORT int playerc_limb_power(playerc_limb_t *device, uint32_t enable)
Turn the power to the limb on or off.
PLAYERC_EXPORT int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length)
Command the end effector to move along the provided vector from its current position for the provided...
PLAYERC_EXPORT int playerc_limb_home_cmd(playerc_limb_t *device)
Command the end effector to move home.
PLAYERC_EXPORT int playerc_limb_subscribe(playerc_limb_t *device, int access)
Subscribe to the limb device.
PLAYERC_EXPORT int playerc_limb_stop_cmd(playerc_limb_t *device)
Command the end effector to stop immediatly.
PLAYERC_EXPORT playerc_limb_t * playerc_limb_create(playerc_client_t *client, int index)
Create a limb proxy.
PLAYERC_EXPORT int playerc_limb_setpose_cmd(playerc_limb_t *device, float pX, float pY, float pZ, float aX, float aY, float aZ, float oX, float oY, float oZ)
Command the end effector to move to a specified pose.
PLAYERC_EXPORT int playerc_limb_get_geom(playerc_limb_t *device)
Get the limb geometry.
PLAYERC_EXPORT int playerc_limb_unsubscribe(playerc_limb_t *device)
Un-subscribe from the limb device.
PLAYERC_EXPORT int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ)
Command the end effector to move to a specified position (ignoring approach and orientation vectors).
struct playerc_localize_particle playerc_localize_particle_t
Hypothesis data.
PLAYERC_EXPORT int playerc_localize_unsubscribe(playerc_localize_t *device)
Un-subscribe from the localize device.
PLAYERC_EXPORT playerc_localize_t * playerc_localize_create(playerc_client_t *client, int index)
Create a localize proxy.
PLAYERC_EXPORT int playerc_localize_subscribe(playerc_localize_t *device, int access)
Subscribe to the localize device.
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[6])
Set the the robot pose (mean and covariance).
PLAYERC_EXPORT void playerc_localize_destroy(playerc_localize_t *device)
Destroy a localize proxy.
PLAYERC_EXPORT playerc_log_t * playerc_log_create(playerc_client_t *client, int index)
Create a log proxy.
PLAYERC_EXPORT int playerc_log_subscribe(playerc_log_t *device, int access)
Subscribe to the log device.
PLAYERC_EXPORT int playerc_log_set_write_state(playerc_log_t *device, int state)
Start/stop logging.
PLAYERC_EXPORT int playerc_log_set_read_state(playerc_log_t *device, int state)
Start/stop playback.
PLAYERC_EXPORT int playerc_log_set_filename(playerc_log_t *device, const char *fname)
Change name of log file to write to.
PLAYERC_EXPORT int playerc_log_unsubscribe(playerc_log_t *device)
Un-subscribe from the log device.
PLAYERC_EXPORT int playerc_log_get_state(playerc_log_t *device)
Get logging/playback state.
PLAYERC_EXPORT int playerc_log_set_read_rewind(playerc_log_t *device)
Rewind playback.
PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device)
Destroy a log proxy.
PLAYERC_EXPORT int playerc_map_subscribe(playerc_map_t *device, int access)
Subscribe to the map device.
PLAYERC_EXPORT int playerc_map_unsubscribe(playerc_map_t *device)
Un-subscribe from the map device.
PLAYERC_EXPORT void playerc_map_destroy(playerc_map_t *device)
Destroy a map proxy.
PLAYERC_EXPORT int playerc_map_get_vector(playerc_map_t *device)
Get the vector map, which is stored in the proxy.
PLAYERC_EXPORT playerc_map_t * playerc_map_create(playerc_client_t *client, int index)
Create a map proxy.
PLAYERC_EXPORT int playerc_map_get_map(playerc_map_t *device)
Get the map, which is stored in the proxy.
PLAYERC_EXPORT int playerc_opaque_subscribe(playerc_opaque_t *device, int access)
Subscribe to the opaque device.
PLAYERC_EXPORT int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data)
Send a generic command.
PLAYERC_EXPORT int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply)
Send a generic request.
PLAYERC_EXPORT playerc_opaque_t * playerc_opaque_create(playerc_client_t *client, int index)
Create an opaque device proxy.
PLAYERC_EXPORT void playerc_opaque_destroy(playerc_opaque_t *device)
Destroy an opaque device proxy.
PLAYERC_EXPORT int playerc_opaque_unsubscribe(playerc_opaque_t *device)
Un-subscribe from the opaque device.
PLAYERC_EXPORT playerc_planner_t * playerc_planner_create(playerc_client_t *client, int index)
Create a planner device proxy.
PLAYERC_EXPORT int playerc_planner_enable(playerc_planner_t *device, int state)
Enable / disable the robot's motion.
PLAYERC_EXPORT int playerc_planner_get_waypoints(playerc_planner_t *device)
Get the list of waypoints.
PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access)
Subscribe to the planner device.
PLAYERC_EXPORT void playerc_planner_destroy(playerc_planner_t *device)
Destroy a planner device proxy.
PLAYERC_EXPORT int playerc_planner_set_cmd_pose(playerc_planner_t *device, double gx, double gy, double ga)
Set the goal pose (gx, gy, ga)
PLAYERC_EXPORT int playerc_planner_unsubscribe(playerc_planner_t *device)
Un-subscribe from the planner device.
PLAYERC_EXPORT int playerc_planner_set_cmd_start(playerc_planner_t *device, double sx, double sy, double sa)
Set the start pose (sx, sy, sa)
PLAYERC_EXPORT int playerc_pointcloud3d_subscribe(playerc_pointcloud3d_t *device, int access)
Subscribe to the pointcloud3d device.
PLAYERC_EXPORT void playerc_pointcloud3d_destroy(playerc_pointcloud3d_t *device)
Destroy a pointcloud3d proxy.
player_pointcloud3d_element_t playerc_pointcloud3d_element_t
Structure describing a single 3D pointcloud element.
Definition playerc.h:3682
PLAYERC_EXPORT playerc_pointcloud3d_t * playerc_pointcloud3d_create(playerc_client_t *client, int index)
Create a pointcloud3d proxy.
PLAYERC_EXPORT int playerc_pointcloud3d_unsubscribe(playerc_pointcloud3d_t *device)
Un-subscribe from the pointcloud3d device.
PLAYERC_EXPORT int playerc_position1d_set_cmd_pos(playerc_position1d_t *device, double pos, int state)
Set the target position.
PLAYERC_EXPORT int playerc_position1d_set_cmd_vel(playerc_position1d_t *device, double vel, int state)
Set the target speed.
PLAYERC_EXPORT int playerc_position1d_set_odom(playerc_position1d_t *device, double odom)
Set the odometry offset.
PLAYERC_EXPORT playerc_position1d_t * playerc_position1d_create(playerc_client_t *client, int index)
Create a position1d device proxy.
PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable)
Enable/disable the motors.
PLAYERC_EXPORT int playerc_position1d_subscribe(playerc_position1d_t *device, int access)
Subscribe to the position1d device.
PLAYERC_EXPORT int playerc_position1d_get_geom(playerc_position1d_t *device)
Get the position1d geometry.
PLAYERC_EXPORT int playerc_position1d_set_cmd_pos_with_vel(playerc_position1d_t *device, double pos, double vel, int state)
Set the target position with movement velocity -.
PLAYERC_EXPORT void playerc_position1d_destroy(playerc_position1d_t *device)
Destroy a position1d device proxy.
PLAYERC_EXPORT int playerc_position1d_unsubscribe(playerc_position1d_t *device)
Un-subscribe from the position1d device.
PLAYERC_EXPORT int playerc_position2d_set_cmd_car(playerc_position2d_t *device, double vx, double a)
Set the target cmd for car like position.
PLAYERC_EXPORT int playerc_position2d_get_geom(playerc_position2d_t *device)
Get the position2d geometry.
PLAYERC_EXPORT playerc_position2d_t * playerc_position2d_create(playerc_client_t *client, int index)
Create a position2d device proxy.
PLAYERC_EXPORT int playerc_position2d_subscribe(playerc_position2d_t *device, int access)
Subscribe to the position2d device.
PLAYERC_EXPORT int playerc_position2d_set_odom(playerc_position2d_t *device, double ox, double oy, double oa)
Set the odometry offset.
PLAYERC_EXPORT int playerc_position2d_set_cmd_vel_head(playerc_position2d_t *device, double vx, double vy, double pa, int state)
Set the target speed and heading.
PLAYERC_EXPORT int playerc_position2d_unsubscribe(playerc_position2d_t *device)
Un-subscribe from the position2d device.
PLAYERC_EXPORT void playerc_position2d_destroy(playerc_position2d_t *device)
Destroy a position2d device proxy.
PLAYERC_EXPORT int playerc_position2d_enable(playerc_position2d_t *device, int enable)
Enable/disable the motors.
PLAYERC_EXPORT int playerc_position2d_set_cmd_vel(playerc_position2d_t *device, double vx, double vy, double va, int state)
Set the target speed.
PLAYERC_EXPORT int playerc_position2d_set_cmd_pose_with_vel(playerc_position2d_t *device, player_pose2d_t pos, player_pose2d_t vel, int state)
Set the target pose with given motion vel.
PLAYERC_EXPORT int playerc_position2d_set_cmd_pose(playerc_position2d_t *device, double gx, double gy, double ga, int state)
Set the target pose (gx, gy, ga) is the target pose in the odometric coordinate system.
PLAYERC_EXPORT int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode)
Set the velocity mode.
PLAYERC_EXPORT int playerc_position3d_unsubscribe(playerc_position3d_t *device)
Un-subscribe from the position3d device.
PLAYERC_EXPORT int playerc_position3d_get_geom(playerc_position3d_t *device)
Get the position3d geometry.
PLAYERC_EXPORT int playerc_position3d_reset_odom(playerc_position3d_t *device)
Reset the odometry offset.
PLAYERC_EXPORT int playerc_position3d_subscribe(playerc_position3d_t *device, int access)
Subscribe to the position3d device.
PLAYERC_EXPORT int playerc_position3d_set_pose_with_vel(playerc_position3d_t *device, player_pose3d_t pos, player_pose3d_t vel)
Set the target pose (pos,vel) define desired position and motion speed.
PLAYERC_EXPORT int playerc_position3d_set_velocity(playerc_position3d_t *device, double vx, double vy, double vz, double vr, double vp, double vt, int state)
Set the target speed.
PLAYERC_EXPORT int playerc_position3d_set_odom(playerc_position3d_t *device, double ox, double oy, double oz, double oroll, double opitch, double oyaw)
Set the odometry offset.
PLAYERC_EXPORT playerc_position3d_t * playerc_position3d_create(playerc_client_t *client, int index)
Create a position3d device proxy.
PLAYERC_EXPORT int playerc_position3d_enable(playerc_position3d_t *device, int enable)
Enable/disable the motors.
PLAYERC_EXPORT int playerc_position3d_set_pose(playerc_position3d_t *device, double gx, double gy, double gz, double gr, double gp, double gt)
Set the target pose (gx, gy, ga, gr, gp, gt) is the target pose in the odometric coordinate system.
PLAYERC_EXPORT int playerc_position3d_set_cmd_pose(playerc_position3d_t *device, double gx, double gy, double gz)
For compatibility with old position3d interface.
PLAYERC_EXPORT int playerc_position3d_set_speed(playerc_position3d_t *device, double vx, double vy, double vz, int state)
For compatibility with old position3d interface.
PLAYERC_EXPORT void playerc_position3d_destroy(playerc_position3d_t *device)
Destroy a position3d device proxy.
PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access)
Subscribe to the power device.
PLAYERC_EXPORT void playerc_power_destroy(playerc_power_t *device)
Destroy a power device proxy.
PLAYERC_EXPORT playerc_power_t * playerc_power_create(playerc_client_t *client, int index)
Create a power device proxy.
PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device)
Un-subscribe from the power device.
PLAYERC_EXPORT int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom, double panspeed, double tiltspeed)
Set the pan, tilt and zoom values (and speed)
PLAYERC_EXPORT int playerc_ptz_query_status(playerc_ptz_t *device)
Query the pan and tilt status.
PLAYERC_EXPORT int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom)
Set the pan, tilt and zoom values.
PLAYERC_EXPORT int playerc_ptz_unsubscribe(playerc_ptz_t *device)
Un-subscribe from the ptz device.
PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device)
Destroy a ptz proxy.
PLAYERC_EXPORT int playerc_ptz_subscribe(playerc_ptz_t *device, int access)
Subscribe to the ptz device.
PLAYERC_EXPORT playerc_ptz_t * playerc_ptz_create(playerc_client_t *client, int index)
Create a ptz proxy.
PLAYERC_EXPORT int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode)
Change control mode (select velocity or position control)
PLAYERC_EXPORT int playerc_ranger_unsubscribe(playerc_ranger_t *device)
Un-subscribe from the ranger device.
PLAYERC_EXPORT int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle, double *max_angle, double *angular_res, double *min_range, double *max_range, double *range_res, double *frequency)
Get the ranger device's configuration.
PLAYERC_EXPORT int playerc_ranger_subscribe(playerc_ranger_t *device, int access)
Subscribe to the ranger device.
PLAYERC_EXPORT int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle, double max_angle, double angular_res, double min_range, double max_range, double range_res, double frequency)
Set the ranger device's configuration.
PLAYERC_EXPORT void playerc_ranger_destroy(playerc_ranger_t *device)
Destroy a ranger proxy.
PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device)
Get the ranger geometry.
PLAYERC_EXPORT int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value)
Turn device power on or off.
PLAYERC_EXPORT int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value)
Turn intensity data on or off.
PLAYERC_EXPORT playerc_ranger_t * playerc_ranger_create(playerc_client_t *client, int index)
Create a ranger proxy.
PLAYERC_EXPORT int playerc_rfid_unsubscribe(playerc_rfid_t *device)
Un-subscribe from the rfid device.
PLAYERC_EXPORT void playerc_rfid_destroy(playerc_rfid_t *device)
Destroy a rfid proxy.
PLAYERC_EXPORT int playerc_rfid_subscribe(playerc_rfid_t *device, int access)
Subscribe to the rfid device.
PLAYERC_EXPORT playerc_rfid_t * playerc_rfid_create(playerc_client_t *client, int index)
Create a rfid proxy.
PLAYERC_EXPORT int playerc_simulation_get_pose2d(playerc_simulation_t *device, char *identifier, double *x, double *y, double *a)
Get the 2D pose of a named simulation object.
PLAYERC_EXPORT int playerc_simulation_unsubscribe(playerc_simulation_t *device)
Un-subscribe from the simulation device.
PLAYERC_EXPORT int playerc_simulation_pause(playerc_simulation_t *device)
pause / unpause the simulation
PLAYERC_EXPORT int playerc_simulation_get_pose3d(playerc_simulation_t *device, char *identifier, double *x, double *y, double *z, double *roll, double *pitch, double *yaw, double *time)
Get the 3D pose of a named simulation object.
PLAYERC_EXPORT int playerc_simulation_get_property(playerc_simulation_t *device, char *name, char *property, void *value, size_t value_len)
Get a property value.
PLAYERC_EXPORT int playerc_simulation_reset(playerc_simulation_t *device)
reset the simulation state
PLAYERC_EXPORT playerc_simulation_t * playerc_simulation_create(playerc_client_t *client, int index)
Create a new simulation proxy.
PLAYERC_EXPORT int playerc_simulation_set_pose3d(playerc_simulation_t *device, char *name, double gx, double gy, double gz, double groll, double gpitch, double gyaw)
Set the 3D pose of a named simulation object.
PLAYERC_EXPORT int playerc_simulation_set_pose2d(playerc_simulation_t *device, char *name, double gx, double gy, double ga)
Set the 2D pose of a named simulation object.
PLAYERC_EXPORT int playerc_simulation_subscribe(playerc_simulation_t *device, int access)
Subscribe to the simulation device.
PLAYERC_EXPORT void playerc_simulation_destroy(playerc_simulation_t *device)
Destroy a simulation proxy.
PLAYERC_EXPORT int playerc_simulation_save(playerc_simulation_t *device)
make the simulation save the status/world
PLAYERC_EXPORT int playerc_simulation_set_property(playerc_simulation_t *device, char *name, char *property, void *value, size_t value_len)
Set a property value.
PLAYERC_EXPORT playerc_sonar_t * playerc_sonar_create(playerc_client_t *client, int index)
Create a sonar proxy.
PLAYERC_EXPORT int playerc_sonar_unsubscribe(playerc_sonar_t *device)
Un-subscribe from the sonar device.
PLAYERC_EXPORT void playerc_sonar_destroy(playerc_sonar_t *device)
Destroy a sonar proxy.
PLAYERC_EXPORT int playerc_sonar_subscribe(playerc_sonar_t *device, int access)
Subscribe to the sonar device.
PLAYERC_EXPORT int playerc_sonar_get_geom(playerc_sonar_t *device)
Get the sonar geometry.
PLAYERC_EXPORT int playerc_speechrecognition_unsubscribe(playerc_speechrecognition_t *device)
Un-subscribe from the speech recognition device.
PLAYERC_EXPORT void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device)
Destroy a speech recognition proxy.
PLAYERC_EXPORT int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access)
Subscribe to the speech recognition device.
PLAYERC_EXPORT playerc_speechrecognition_t * playerc_speechrecognition_create(playerc_client_t *client, int index)
Create a speech recognition proxy.
PLAYERC_EXPORT playerc_speech_t * playerc_speech_create(playerc_client_t *client, int index)
Create a speech proxy.
PLAYERC_EXPORT int playerc_speech_say(playerc_speech_t *device, char *)
Set the output for the speech device.
PLAYERC_EXPORT int playerc_speech_unsubscribe(playerc_speech_t *device)
Un-subscribe from the speech device.
PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device)
Destroy a speech proxy.
PLAYERC_EXPORT int playerc_speech_subscribe(playerc_speech_t *device, int access)
Subscribe to the speech device.
PLAYERC_EXPORT playerc_stereo_t * playerc_stereo_create(playerc_client_t *client, int index)
Create a stereo proxy.
player_pointcloud3d_stereo_element_t playerc_pointcloud3d_stereo_element_t
Structure describing a single 3D pointcloud element.
Definition playerc.h:3722
PLAYERC_EXPORT int playerc_stereo_subscribe(playerc_stereo_t *device, int access)
Subscribe to the stereo device.
PLAYERC_EXPORT void playerc_stereo_destroy(playerc_stereo_t *device)
Destroy a stereo proxy.
PLAYERC_EXPORT int playerc_stereo_unsubscribe(playerc_stereo_t *device)
Un-subscribe from the stereo device.
PLAYERC_EXPORT int playerc_vectormap_unsubscribe(playerc_vectormap_t *device)
Un-subscribe from the vectormap device.
PLAYERC_EXPORT int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access)
Subscribe to the vectormap device.
PLAYERC_EXPORT int playerc_vectormap_get_map_info(playerc_vectormap_t *device)
Get the vectormap metadata, which is stored in the proxy.
PLAYERC_EXPORT int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index)
Get the layer data by index.
PLAYERC_EXPORT uint8_t * playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index)
Get an individual feature as a WKB geometry.
PLAYERC_EXPORT playerc_vectormap_t * playerc_vectormap_create(playerc_client_t *client, int index)
Create a vectormap proxy.
PLAYERC_EXPORT void playerc_vectormap_destroy(playerc_vectormap_t *device)
Destroy a vectormap proxy.
PLAYERC_EXPORT void playerc_vectormap_cleanup(playerc_vectormap_t *device)
Clean up the dynamically allocated memory for the vectormap.
PLAYERC_EXPORT int playerc_vectormap_write_layer(playerc_vectormap_t *device, const player_vectormap_layer_data_t *data)
Write layer data.
PLAYERC_EXPORT void playerc_wifi_destroy(playerc_wifi_t *device)
Destroy a wifi proxy.
PLAYERC_EXPORT playerc_wifi_link_t * playerc_wifi_get_link(playerc_wifi_t *device, int link)
Get link state.
PLAYERC_EXPORT playerc_wifi_t * playerc_wifi_create(playerc_client_t *client, int index)
Create a wifi proxy.
PLAYERC_EXPORT int playerc_wifi_unsubscribe(playerc_wifi_t *device)
Un-subscribe from the wifi device.
PLAYERC_EXPORT int playerc_wifi_subscribe(playerc_wifi_t *device, int access)
Subscribe to the wifi device.
PLAYERC_EXPORT int playerc_wsn_subscribe(playerc_wsn_t *device, int access)
Subscribe to the wsn device.
PLAYERC_EXPORT int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id, int group_id, int devnr, int state)
Set the device state.
PLAYERC_EXPORT playerc_wsn_t * playerc_wsn_create(playerc_client_t *client, int index)
Create a wsn proxy.
PLAYERC_EXPORT int playerc_wsn_datatype(playerc_wsn_t *device, int value)
Change the data type to RAW or converted engineering units.
PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id, double frequency)
Change data delivery frequency.
PLAYERC_EXPORT int playerc_wsn_unsubscribe(playerc_wsn_t *device)
Un-subscribe from the wsn device.
PLAYERC_EXPORT void playerc_wsn_destroy(playerc_wsn_t *device)
Destroy a wsn proxy.
PLAYERC_EXPORT int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id, int value)
Put the node in sleep mode (0) or wake it up (1).
PLAYERC_EXPORT int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace)
Get the name for a given interface code.
PLAYERC_EXPORT const char * playerc_error_str(void)
Retrieve the last error (as a descriptive string).
struct player_blackboard_entry player_blackboard_entry_t
Vectormap feature data.
Client object data.
Definition playerc.h:508
double lasttime
Server time stamp on the previous packet.
Definition playerc.h:573
char * data
Definition playerc.h:565
int connected
Whether or not we're currently connected.
Definition playerc.h:521
uint32_t overflow_count
How many messages were lost on the server due to overflows, incremented by player,...
Definition playerc.h:533
int retry_limit
How many times we'll try to reconnect after a socket error.
Definition playerc.h:526
double retry_time
How long to sleep, in seconds, to sleep between reconnect attempts.
Definition playerc.h:530
double datatime
Server time stamp on the last packet.
Definition playerc.h:571
struct _playerc_device_t * device[PLAYER_MAX_DEVICES]
List of subscribed devices.
Definition playerc.h:557
int sock
Definition playerc.h:537
int data_requested
Definition playerc.h:544
int data_received
Definition playerc.h:548
char * host
Server address.
Definition playerc.h:514
void * id
A useful ID for identifying devices; mostly used by other language bindings.
Definition playerc.h:511
uint8_t mode
Definition playerc.h:540
playerc_device_info_t devinfos[PLAYER_MAX_DEVICES]
List of available (but not necessarily subscribed) devices.
Definition playerc.h:553
playerc_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE]
Definition playerc.h:561
Common device info.
Definition playerc.h:865
double lasttime
Data timestamp from the previous data.
Definition playerc.h:888
int fresh
Freshness flag.
Definition playerc.h:893
playerc_client_t * client
Pointer to the client proxy.
Definition playerc.h:872
int subscribed
The subscribe flag is non-zero if the device has been successfully subscribed (read-only).
Definition playerc.h:882
int freshconfig
Freshness flag.
Definition playerc.h:901
char drivername[PLAYER_MAX_DRIVER_STRING_LEN]
The driver name.
Definition playerc.h:878
playerc_putmsg_fn_t putmsg
Standard message callback for this device.
Definition playerc.h:904
void * id
A useful ID for identifying devices; mostly used by other language bindings.
Definition playerc.h:869
void * user_data
Extra user data for this device.
Definition playerc.h:907
int freshgeom
Freshness flag.
Definition playerc.h:897
double datatime
Data timestamp, i.e., the time at which the data was generated (s).
Definition playerc.h:885
int callback_count
Extra callbacks for this device.
Definition playerc.h:910
player_devaddr_t addr
Device address.
Definition playerc.h:875
A rectangular bounding box, used to define the size of an object.
Definition player.h:255
Vectormap feature data.
Definition player.h:266
A color descriptor.
Definition player.h:321
A device address.
Definition player.h:146
A rectangular bounding box, used to define the origin and bounds of an object.
Definition player.h:308
Generic message header.
Definition player.h:162
An angle in 3D space.
Definition player.h:207
A point in the plane.
Definition player.h:185
A point in 3D space.
Definition player.h:195
A pose in the plane.
Definition player.h:218
A pose in space.
Definition player.h:229
A line segment, used to construct vector-based maps.
Definition player.h:292
Actarray device data.
Definition playerc.h:1037
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1039
player_orientation_3d_t base_orientation
The orientation of the base of the actarray.
Definition playerc.h:1053
uint32_t actuators_count
The number of actuators in the array.
Definition playerc.h:1042
player_point_3d_t base_pos
The position of the base of the actarray.
Definition playerc.h:1051
uint8_t motor_state
Reports if the actuators are off (0) or on (1)
Definition playerc.h:1049
uint32_t actuators_geom_count
The number of actuators we have geometry for.
Definition playerc.h:1046
player_actarray_actuator_t * actuators_data
The actuator data, geometry and motor state.
Definition playerc.h:1044
Aio proxy data.
Definition playerc.h:980
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:982
Audio device data.
Definition playerc.h:1131
player_audio_seq_t seq_data
last block of seq data
Definition playerc.h:1142
player_audio_mixer_channel_list_detail_t channel_details_list
Details of the channels from the mixer.
Definition playerc.h:1136
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition playerc.h:1145
uint32_t state
current driver state
Definition playerc.h:1148
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1133
player_audio_wav_t wav_data
last block of recorded data
Definition playerc.h:1139
BlackBoard proxy.
Definition playerc.h:1229
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1231
void * py_private
Kludge to get around python callback issues.
Definition playerc.h:1235
void(* on_blackboard_event)(struct playerc_blackboard *, player_blackboard_entry_t)
Function to be called when a key is updated.
Definition playerc.h:1233
Blinklight proxy data.
Definition playerc.h:1290
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1292
Blobfinder device data.
Definition playerc.h:1346
unsigned int blobs_count
A list of detected blobs.
Definition playerc.h:1354
unsigned int width
Image dimensions (pixels).
Definition playerc.h:1351
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1348
Bumper proxy data.
Definition playerc.h:1389
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition playerc.h:1405
int bumper_count
Number of points in the scan.
Definition playerc.h:1402
int pose_count
Number of pose values.
Definition playerc.h:1394
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1391
player_bumper_define_t * poses
Pose of each bumper relative to robot (mm, mm, deg, mm, mm).
Definition playerc.h:1399
Camera proxy data.
Definition playerc.h:1446
int image_count
Size of image data (bytes)
Definition playerc.h:1468
uint8_t * image
Image data (byte aligned, row major order).
Definition playerc.h:1474
int bpp
Image bits-per-pixel (8, 16, 24).
Definition playerc.h:1454
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1448
int fdiv
Some images (such as disparity maps) use scaled pixel values; for these images, fdiv specifies the sc...
Definition playerc.h:1462
int width
Image dimensions (pixels).
Definition playerc.h:1451
int format
Image format (e.g., RGB888).
Definition playerc.h:1457
int compression
Image compression method.
Definition playerc.h:1465
Definition playerc.h:431
Note: the structure describing the Cooperating Object's data packet is declared in Player.
Definition playerc.h:1533
uint8_t command
Command type.
Definition playerc.h:1582
uint8_t * user_data
User defined data array.
Definition playerc.h:1579
uint32_t sensor_data_count
Number of sensors included.
Definition playerc.h:1568
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1535
uint32_t user_data_count
User defined message size (in bytes)
Definition playerc.h:1577
int messageType
Flag to indicate that new info has come.
Definition playerc.h:1538
uint32_t alarm_data_count
Number of alarms included.
Definition playerc.h:1572
player_coopobject_sensor_t * alarm_data
Active alarms array.
Definition playerc.h:1574
uint16_t id
Cooperating Object ID.
Definition playerc.h:1547
uint16_t RSSIsender
Cooperating Object data packet.
Definition playerc.h:1554
uint8_t request
Request type.
Definition playerc.h:1584
uint8_t * parameters
Request/command parameters array
Definition playerc.h:1588
float x
Cooperating Object Position.
Definition playerc.h:1561
uint16_t parent_id
Cooperating Object Parent ID (if existing)
Definition playerc.h:1549
uint8_t origin
The type of Cooperating Object.
Definition playerc.h:1545
uint32_t parameters_count
Request/command parameters array size (in bytes)
Definition playerc.h:1586
player_coopobject_sensor_t * sensor_data
Sensor measurements array.
Definition playerc.h:1570
Info about an available (but not necessarily subscribed) device.
Definition playerc.h:496
player_devaddr_t addr
Player id of the device.
Definition playerc.h:498
Dio proxy data.
Definition playerc.h:1640
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1642
Fiducial finder data.
Definition playerc.h:1689
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1691
player_fiducial_geom_t fiducial_geom
Geometry in robot cs.
Definition playerc.h:1697
int fiducials_count
List of detected beacons.
Definition playerc.h:1700
GPS proxy data.
Definition playerc.h:1742
double hdop
Horizontal dilution of precision.
Definition playerc.h:1769
double err_horz
Horizontal and vertical error (meters).
Definition playerc.h:1775
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1744
int sat_count
Number of satellites in view.
Definition playerc.h:1781
double speed
Speed over ground, in m/s.
Definition playerc.h:1759
double course
Course made good (heading if the robot moves along its longitudinal axis), in radians.
Definition playerc.h:1763
double alt
Altitude (meters).
Definition playerc.h:1756
double utm_e
UTM easting and northing (meters).
Definition playerc.h:1766
double vdop
Vertical dilution of precision.
Definition playerc.h:1772
double lat
Latitude and logitude (degrees).
Definition playerc.h:1752
int quality
Quality of fix 0 = invalid, 1 = GPS fix, 2 = DGPS fix.
Definition playerc.h:1778
double utc_time
UTC time (seconds since the epoch)
Definition playerc.h:1747
Graphics2d device data.
Definition playerc.h:1813
player_color_t color
current drawing color
Definition playerc.h:1818
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1815
Graphics3d device data.
Definition playerc.h:1880
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1882
player_color_t color
current drawing color
Definition playerc.h:1885
Gripper device data.
Definition playerc.h:1936
uint8_t capacity
The capacity of the gripper's store - if 0, the gripper cannot store.
Definition playerc.h:1952
uint8_t num_beams
The number of breakbeams the gripper has.
Definition playerc.h:1950
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:1938
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition playerc.h:1946
uint8_t stored
The number of currently-stored objects.
Definition playerc.h:1961
uint8_t state
The gripper's state: may be one of PLAYER_GRIPPER_STATE_OPEN, PLAYER_GRIPPER_STATE_CLOSED,...
Definition playerc.h:1957
uint32_t beams
The position of the object in the gripper.
Definition playerc.h:1959
Note: the structure describing the HEALTH's data packet is declared in Player.
Definition playerc.h:2019
player_health_memory_t mem
The memory stats
Definition playerc.h:2025
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2021
player_health_cpu_t cpu_usage
The current cpu usage
Definition playerc.h:2023
player_health_memory_t swap
The swap stats
Definition playerc.h:2027
IMU proxy state data.
Definition playerc.h:3771
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition playerc.h:3781
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3773
float q0
Orientation data as quaternions
Definition playerc.h:3784
player_pose3d_t pose
The complete pose of the IMU in 3D coordinates + angles
Definition playerc.h:3776
Ir proxy data.
Definition playerc.h:2060
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2062
joystick proxy data.
Definition playerc.h:2109
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2111
Laser proxy data.
Definition playerc.h:2154
int * intensity
Scan reflection intensity values (0-3).
Definition playerc.h:2200
player_point_2d_t * point
Scan data; x, y position (m).
Definition playerc.h:2195
double range_res
Range resolution, in m.
Definition playerc.h:2180
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam,...
Definition playerc.h:2211
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2156
int scan_count
Number of points in the scan.
Definition playerc.h:2171
double max_range
Maximum range of sensor, in m.
Definition playerc.h:2183
double * ranges
Raw range data; range (m).
Definition playerc.h:2189
int intensity_on
Is intesity data returned.
Definition playerc.h:2168
double scan_res
Angular resolution in radians.
Definition playerc.h:2177
double min_left
Minimum range, in meters, in the left half of the scan (those ranges from the first beam after the mi...
Definition playerc.h:2216
double scan_start
Start bearing of the scan (radians).
Definition playerc.h:2174
int scan_id
ID for this scan.
Definition playerc.h:2203
double scanning_frequency
Scanning frequency in Hz.
Definition playerc.h:2186
int laser_id
Laser IDentification information.
Definition playerc.h:2206
Limb device data.
Definition playerc.h:2326
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2328
Hypothesis data.
Definition playerc.h:2400
Localization device data.
Definition playerc.h:2408
int8_t * map_cells
Map data (empty = -1, unknown = 0, occupied = +1).
Definition playerc.h:2422
double map_scale
Map scale (m/cell).
Definition playerc.h:2416
double pending_time
The timestamp on the last reading processed.
Definition playerc.h:2428
int pending_count
The number of pending (unprocessed) sensor readings.
Definition playerc.h:2425
int map_size_x
Map dimensions (cells).
Definition playerc.h:2413
int map_tile_x
Next map tile to read.
Definition playerc.h:2419
int hypoth_count
List of possible poses.
Definition playerc.h:2431
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2410
Log proxy data.
Definition playerc.h:2476
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition playerc.h:2482
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2478
int state
Is logging/playback enabled? Call playerc_log_get_state() to fill it.
Definition playerc.h:2486
Map proxy data.
Definition playerc.h:2536
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2538
double vminx
Vector-based version of the map (call playerc_map_get_vector() to fill this in).
Definition playerc.h:2557
char * cells
Occupancy for each cell.
Definition playerc.h:2553
int8_t data_range
Value for each cell (-range <= EMPTY < 0, unknown = 0, 0 < OCCUPIED <= range)
Definition playerc.h:2550
double resolution
Map resolution, m/cell.
Definition playerc.h:2541
int width
Map size, in cells.
Definition playerc.h:2544
Definition playerc.h:439
Opaque device data.
Definition playerc.h:2657
int data_count
Size of data (bytes)
Definition playerc.h:2662
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2659
uint8_t * data
Data
Definition playerc.h:2665
Planner device data.
Definition playerc.h:2706
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2708
double wx
Current waypoint location (m, m, radians)
Definition playerc.h:2723
double px
Current pose (m, m, radians).
Definition playerc.h:2717
double waypoint_distance
Straight-line distance along allwaypoints in the current plan.
Definition playerc.h:2739
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition playerc.h:2728
int waypoint_count
Number of waypoints in the plan.
Definition playerc.h:2731
int path_valid
Did the planner find a valid path?
Definition playerc.h:2711
double gx
Goal location (m, m, radians)
Definition playerc.h:2720
int path_done
Have we arrived at the goal?
Definition playerc.h:2714
pointcloud3d proxy data.
Definition playerc.h:3686
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition playerc.h:3694
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition playerc.h:3691
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3688
Position1d device data.
Definition playerc.h:2793
double vel
Odometric velocity [m/s] or [rad/s].
Definition playerc.h:2807
double pos
Odometric pose [m] or [rad].
Definition playerc.h:2804
int status
Status bitfield of extra data in the following order:
Definition playerc.h:2823
int stall
Stall flag [0, 1].
Definition playerc.h:2810
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2795
Position2d device data.
Definition playerc.h:2887
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition playerc.h:2901
int stall
Stall flag [0, 1].
Definition playerc.h:2904
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2889
double px
Odometric pose (m, m, rad).
Definition playerc.h:2898
Position3d device data.
Definition playerc.h:2982
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2984
double vel_roll
Angular velocity (radians/sec).
Definition playerc.h:3002
double pos_roll
Device orientation (radians).
Definition playerc.h:2996
double pos_x
Device position (m).
Definition playerc.h:2993
int stall
Stall flag [0, 1].
Definition playerc.h:3005
double vel_x
Linear velocity (m/s).
Definition playerc.h:2999
Power device data.
Definition playerc.h:3086
int valid
status bits.
Definition playerc.h:3092
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3088
double watts
power currently being used (Watts).
Definition playerc.h:3105
double percent
Battery charge (percent full).
Definition playerc.h:3098
double charge
Battery charge (Volts).
Definition playerc.h:3095
int charging
charging flag.
Definition playerc.h:3108
double joules
energy stored (Joules)
Definition playerc.h:3101
PTZ device data.
Definition playerc.h:3143
int status
The current pan and tilt status.
Definition playerc.h:3156
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3145
double zoom
The current zoom value (field of view angle).
Definition playerc.h:3153
double pan
The current ptz pan and tilt angles.
Definition playerc.h:3150
Ranger proxy data.
Definition playerc.h:3225
uint32_t intensities_count
Number of intensities in a scan.
Definition playerc.h:3265
uint32_t element_count
Number of individual elements in the device.
Definition playerc.h:3230
player_pose3d_t device_pose
Device geometry in the robot CS: pose gives the position and orientation, size gives the extent.
Definition playerc.h:3251
double * intensities
Intensity data [m].
Definition playerc.h:3269
player_pose3d_t * element_poses
Geometry of each individual element in the device (e.g.
Definition playerc.h:3256
double range_res
Range resolution [m].
Definition playerc.h:3244
uint32_t bearings_count
Number of scan bearings.
Definition playerc.h:3272
player_point_3d_t * points
Scan points (x, y, z).
Definition playerc.h:3280
double max_range
Maximum range [m].
Definition playerc.h:3242
double max_angle
End angle of scans [rad].
Definition playerc.h:3235
double * bearings
Scan bearings in the XY plane [radians].
Definition playerc.h:3275
uint32_t points_count
Number of scan points.
Definition playerc.h:3278
uint32_t ranges_count
Number of ranges in a scan.
Definition playerc.h:3260
double min_range
Minimum range [m].
Definition playerc.h:3240
double angular_res
Scan resolution [rad].
Definition playerc.h:3237
double * ranges
Range data [m].
Definition playerc.h:3262
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3227
double frequency
Scanning frequency [Hz].
Definition playerc.h:3246
double min_angle
Start angle of scans [rad].
Definition playerc.h:3233
RFID proxy data.
Definition playerc.h:3645
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3647
uint16_t tags_count
The number of RFID tags found.
Definition playerc.h:3650
playerc_rfidtag_t * tags
The list of RFID tags.
Definition playerc.h:3653
Structure describing a single RFID tag.
Definition playerc.h:3634
uint32_t guid_count
GUID count.
Definition playerc.h:3638
uint8_t * guid
The Globally Unique IDentifier (GUID) of the tag.
Definition playerc.h:3640
uint32_t type
Tag type.
Definition playerc.h:3636
Simulation device proxy.
Definition playerc.h:3484
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3486
Sonar proxy data.
Definition playerc.h:3359
int scan_count
Number of points in the scan.
Definition playerc.h:3371
int pose_count
Number of pose values.
Definition playerc.h:3364
player_pose3d_t * poses
Pose of each sonar relative to robot (m, m, radians).
Definition playerc.h:3368
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3361
double * scan
Scan data: range (m).
Definition playerc.h:3374
Speech proxy data.
Definition playerc.h:3560
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3562
Speech recognition proxy data.
Definition playerc.h:3596
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3598
stereo proxy data.
Definition playerc.h:3726
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3728
Vectormap proxy.
Definition playerc.h:2596
player_vectormap_layer_data_t ** layers_data
Layer data.
Definition playerc.h:2606
player_vectormap_layer_info_t ** layers_info
Layer info.
Definition playerc.h:2608
playerwkbprocessor_t wkbprocessor
WKB processor instance if you want to deal with WKB data.
Definition playerc.h:2610
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:2598
uint32_t layers_count
The number of layers.
Definition playerc.h:2604
player_extent2d_t extent
Boundary area.
Definition playerc.h:2602
uint32_t srid
Spatial reference identifier.
Definition playerc.h:2600
Wifi device proxy.
Definition playerc.h:3441
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3443
playerc_wifi_link_t * links
A list containing info for each link.
Definition playerc.h:3446
Note: the structure describing the WSN node's data packet is declared in Player.
Definition playerc.h:3825
player_wsn_node_data_t data_packet
The WSN node's data packet.
Definition playerc.h:3836
uint32_t node_id
The ID of the WSN node.
Definition playerc.h:3832
uint32_t node_parent_id
The ID of the WSN node's parent (if existing).
Definition playerc.h:3834
uint32_t node_type
The type of WSN node.
Definition playerc.h:3830
playerc_device_t info
Device info; must be at the start of all device structures.
Definition playerc.h:3827