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., 59 Temple Place - Suite 330, Boston, MA 02111-1307, USA.
18  *
19  */
20 
21 /***************************************************************************
22  * Desc: Player client
23  * Author: Andrew Howard
24  * Date: 24 Aug 2001
25  # CVS: $Id: playerc.h 8173 2009-08-04 07:25:00Z gbiggs $
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
95 extern "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 
334 /***************************************************************************/
340 /***************************************************************************/
341 
346 PLAYERC_EXPORT const char *playerc_error_str(void);
347 
349 /*const char *playerc_lookup_name(int code);*/
350 
352 /*int playerc_lookup_code(const char *name);*/
353 
355 PLAYERC_EXPORT int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace);
356 
358 /***************************************************************************/
359 
360 
361 /* Forward declare types*/
362 struct _playerc_client_t;
363 struct _playerc_device_t;
364 
365 
366 /* forward declaration to avoid including <sys/poll.h>, which may not be
367  available when people are building clients against this lib*/
368 struct pollfd;
369 
370 
371 /***************************************************************************/
382 /* Items in incoming data queue.*/
383 typedef struct
384 {
385  player_msghdr_t header;
386  void *data;
388 
389 
390 /* Multi-client data*/
391 typedef struct
392 {
393  /* List of clients being managed*/
394  int client_count;
395  struct _playerc_client_t *client[128];
396 
397  /* Poll info*/
398  struct pollfd* pollfd;
399 
400  /* Latest time received from any server*/
401  double time;
402 
404 
405 /* Create a multi-client object*/
406 PLAYERC_EXPORT playerc_mclient_t *playerc_mclient_create(void);
407 
408 /* Destroy a multi-client object*/
409 PLAYERC_EXPORT void playerc_mclient_destroy(playerc_mclient_t *mclient);
410 
411 /* Add a client to the multi-client (private).*/
412 PLAYERC_EXPORT int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
413 
414 /* Test to see if there is pending data.
415  Returns -1 on error, 0 or 1 otherwise.*/
416 PLAYERC_EXPORT int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
417 
418 /* Read incoming data. The timeout is in ms. Set timeout to a
419  negative value to wait indefinitely.*/
420 PLAYERC_EXPORT int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
421 
423 /***************************************************************************/
424 
425 
426 /***************************************************************************/
439 PLAYERC_EXPORT typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
440 
442 PLAYERC_EXPORT typedef void (*playerc_callback_fn_t) (void *data);
443 
444 
448 typedef struct
449 {
452 
455 
457 
458 
460 typedef struct _playerc_client_t
461 {
464  void *id;
465 
467  char *host;
468  int port;
469  int transport;
470  struct sockaddr_in server;
471 
475 
480 
483  double retry_time;
484 
486  uint32_t overflow_count;
487 
488 
490  int sock;
491 
493  uint8_t mode;
494 
498 
502 
503 
507  int devinfo_count;
508 
511  int device_count;
512 
514  playerc_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE];
515  int qfirst, qlen, qsize;
516 
518  char *data;
519  char *write_xdrdata;
520  char *read_xdrdata;
521  size_t read_xdrdata_len;
522 
523 
525  double datatime;
527  double lasttime;
528 
529  double request_timeout;
530 
532 
533 
550  const char *host, int port);
551 
557 PLAYERC_EXPORT void playerc_client_destroy(playerc_client_t *client);
558 
564  unsigned int transport);
565 
574 PLAYERC_EXPORT int playerc_client_connect(playerc_client_t *client);
575 
585 
593 
608 PLAYERC_EXPORT int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
609 
622 
645 PLAYERC_EXPORT int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
646 
647 
650 PLAYERC_EXPORT int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
651 
652 
655 PLAYERC_EXPORT int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
656 
659 PLAYERC_EXPORT int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
660  playerc_callback_fn_t callback, void *data);
661 
664 PLAYERC_EXPORT int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
665  playerc_callback_fn_t callback, void *data);
666 
679 
682 PLAYERC_EXPORT int playerc_client_subscribe(playerc_client_t *client, int code, int index,
683  int access, char *drivername, size_t len);
684 
687 PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
688 
700  struct _playerc_device_t *device, uint8_t reqtype,
701  const void *req_data, void **rep_data);
702 
713 /*int playerc_client_getresponse(playerc_client_t *client, uint16_t device,
714  uint16_t index, uint16_t sequence, uint8_t * resptype, uint8_t * resp_data, int resp_len);
715 */
727 PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout);
728 
741 PLAYERC_EXPORT int playerc_client_internal_peek(playerc_client_t *client, int timeout);
742 
757 PLAYERC_EXPORT void *playerc_client_read(playerc_client_t *client);
758 
764 PLAYERC_EXPORT int playerc_client_read_nonblock_withproxy(playerc_client_t *client, void ** proxy);
765 
772 PLAYERC_EXPORT void playerc_client_set_request_timeout(playerc_client_t* client, uint32_t seconds);
773 
781 
787 PLAYERC_EXPORT void playerc_client_set_retry_time(playerc_client_t* client, double time);
788 
791 PLAYERC_EXPORT int playerc_client_write(playerc_client_t *client,
792  struct _playerc_device_t *device,
793  uint8_t subtype,
794  void *cmd, double* timestamp);
795 
796 
798 /**************************************************************************/
799 
800 
801 /***************************************************************************/
814 typedef struct _playerc_device_t
815 {
819  void *id;
820 
823 
826 
829 
833 
835  double datatime;
836 
838  double lasttime;
839 
843  int fresh;
852 
855 
857  void *user_data;
858 
861  playerc_callback_fn_t callback[4];
862  void *callback_data[4];
863 
865 
866 
868 PLAYERC_EXPORT void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
869  int code, int index, playerc_putmsg_fn_t putmsg);
870 
872 PLAYERC_EXPORT void playerc_device_term(playerc_device_t *device);
873 
875 PLAYERC_EXPORT int playerc_device_subscribe(playerc_device_t *device, int access);
876 
878 PLAYERC_EXPORT int playerc_device_unsubscribe(playerc_device_t *device);
879 
881 PLAYERC_EXPORT int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype);
882 
884 PLAYERC_EXPORT int playerc_device_get_boolprop(playerc_device_t *device, char *property, BOOL *value);
885 
887 PLAYERC_EXPORT int playerc_device_set_boolprop(playerc_device_t *device, char *property, BOOL value);
888 
890 PLAYERC_EXPORT int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value);
891 
893 PLAYERC_EXPORT int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value);
894 
896 PLAYERC_EXPORT int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value);
897 
899 PLAYERC_EXPORT int playerc_device_set_dblprop(playerc_device_t *device, char *property, double value);
900 
902 PLAYERC_EXPORT int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value);
903 
905 PLAYERC_EXPORT int playerc_device_set_strprop(playerc_device_t *device, char *property, char *value);
906 
907 
909 /**************************************************************************/
910 
911 
912 /***************************************************************************/
917 /***************************************************************************/
918 
919 /**************************************************************************/
929 typedef struct
930 {
933 
934  /* The number of valid analog inputs.*/
935  uint8_t voltages_count;
936 
937  /* A bitfield of the current digital inputs.*/
938  float *voltages;
939 
940 } playerc_aio_t;
941 
942 
944 PLAYERC_EXPORT playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
945 
947 PLAYERC_EXPORT void playerc_aio_destroy(playerc_aio_t *device);
948 
950 PLAYERC_EXPORT int playerc_aio_subscribe(playerc_aio_t *device, int access);
951 
953 PLAYERC_EXPORT int playerc_aio_unsubscribe(playerc_aio_t *device);
954 
956 PLAYERC_EXPORT int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
957 
959 PLAYERC_EXPORT float playerc_aio_get_data(playerc_aio_t *device, uint32_t index);
960 
962 /***************************************************************************/
963 
964 
965 /***************************************************************************/
976 #define PLAYERC_ACTARRAY_NUM_ACTUATORS PLAYER_ACTARRAY_NUM_ACTUATORS
977 #define PLAYERC_ACTARRAY_ACTSTATE_IDLE PLAYER_ACTARRAY_ACTSTATE_IDLE
978 #define PLAYERC_ACTARRAY_ACTSTATE_MOVING PLAYER_ACTARRAY_ACTSTATE_MOVING
979 #define PLAYERC_ACTARRAY_ACTSTATE_BRAKED PLAYER_ACTARRAY_ACTSTATE_BRAKED
980 #define PLAYERC_ACTARRAY_ACTSTATE_STALLED PLAYER_ACTARRAY_ACTSTATE_STALLED
981 #define PLAYERC_ACTARRAY_TYPE_LINEAR PLAYER_ACTARRAY_TYPE_LINEAR
982 #define PLAYERC_ACTARRAY_TYPE_ROTARY PLAYER_ACTARRAY_TYPE_ROTARY
983 
984 
986 typedef struct
987 {
990 
992  uint32_t actuators_count;
997  player_actarray_actuatorgeom_t *actuators_geom;
999  uint8_t motor_state;
1005 
1007 PLAYERC_EXPORT playerc_actarray_t *playerc_actarray_create(playerc_client_t *client, int index);
1008 
1010 PLAYERC_EXPORT void playerc_actarray_destroy(playerc_actarray_t *device);
1011 
1013 PLAYERC_EXPORT int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
1014 
1016 PLAYERC_EXPORT int playerc_actarray_unsubscribe(playerc_actarray_t *device);
1017 
1020 
1023 
1026 PLAYERC_EXPORT int playerc_actarray_get_geom(playerc_actarray_t *device);
1027 
1029 PLAYERC_EXPORT int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
1030 
1032 PLAYERC_EXPORT int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float *positions, int positions_count);
1033 
1035 PLAYERC_EXPORT int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
1036 
1038 PLAYERC_EXPORT int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float *speeds, int speeds_count);
1039 
1041 PLAYERC_EXPORT int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
1042 
1044 PLAYERC_EXPORT int playerc_actarray_current_cmd(playerc_actarray_t *device, int joint, float current);
1045 
1047 PLAYERC_EXPORT int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float *currents, int currents_count);
1048 
1049 
1053 PLAYERC_EXPORT int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
1054 
1056 PLAYERC_EXPORT int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
1057 
1059 PLAYERC_EXPORT int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
1060 
1061 /* Set the accelration of a joint (-1 for all joints) for all subsequent movement commands*/
1062 PLAYERC_EXPORT int playerc_actarray_accel_config(playerc_actarray_t *device, int joint, float accel);
1063 
1064 
1066 /**************************************************************************/
1067 
1068 /***************************************************************************/
1080 typedef struct
1081 {
1084 
1087 
1090 
1093 
1096 
1098  uint32_t state;
1099 
1100  int last_index;
1101 
1102 } playerc_audio_t;
1103 
1105 PLAYERC_EXPORT playerc_audio_t *playerc_audio_create(playerc_client_t *client, int index);
1106 
1108 PLAYERC_EXPORT void playerc_audio_destroy(playerc_audio_t *device);
1109 
1111 PLAYERC_EXPORT int playerc_audio_subscribe(playerc_audio_t *device, int access);
1112 
1114 PLAYERC_EXPORT int playerc_audio_unsubscribe(playerc_audio_t *device);
1115 
1117 PLAYERC_EXPORT int playerc_audio_wav_play_cmd(playerc_audio_t *device, uint32_t data_count, uint8_t data[], uint32_t format);
1118 
1120 PLAYERC_EXPORT int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state);
1121 
1123 PLAYERC_EXPORT int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index);
1124 
1126 PLAYERC_EXPORT int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t * tones);
1127 
1130 
1132 PLAYERC_EXPORT int playerc_audio_mixer_channel_cmd(playerc_audio_t *device, uint32_t index, float amplitude, uint8_t active);
1133 
1136 PLAYERC_EXPORT int playerc_audio_wav_rec(playerc_audio_t *device);
1137 
1139 PLAYERC_EXPORT int playerc_audio_sample_load(playerc_audio_t *device, int index, uint32_t data_count, uint8_t data[], uint32_t format);
1140 
1143 PLAYERC_EXPORT int playerc_audio_sample_retrieve(playerc_audio_t *device, int index);
1144 
1146 PLAYERC_EXPORT int playerc_audio_sample_rec(playerc_audio_t *device, int index, uint32_t length);
1147 
1150 PLAYERC_EXPORT int playerc_audio_get_mixer_levels(playerc_audio_t *device);
1151 
1154 PLAYERC_EXPORT int playerc_audio_get_mixer_details(playerc_audio_t *device);
1155 
1157 /**************************************************************************/
1158 
1168 #define PLAYERC_BLACKBOARD_DATA_TYPE_NONE 0
1169 #define PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE 1
1170 #define PLAYERC_BLACKBOARD_DATA_TYPE_COMPLEX 2
1171 
1172 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_NONE 0
1173 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_STRING 1
1174 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_INT 2
1175 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_DOUBLE 3
1176 
1178 typedef struct playerc_blackboard
1179 {
1185  void *py_private;
1187 
1189 PLAYERC_EXPORT playerc_blackboard_t *playerc_blackboard_create(playerc_client_t *client, int index);
1190 
1192 PLAYERC_EXPORT void playerc_blackboard_destroy(playerc_blackboard_t *device);
1193 
1195 PLAYERC_EXPORT int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access);
1196 
1198 PLAYERC_EXPORT int playerc_blackboard_unsubscribe(playerc_blackboard_t *device);
1199 
1202 PLAYERC_EXPORT int playerc_blackboard_subscribe_to_key(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1203 
1206 PLAYERC_EXPORT int playerc_blackboard_get_entry(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1207 
1209 PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char* key, const char* group);
1210 
1212 PLAYERC_EXPORT int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char* group);
1213 
1215 PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char* group);
1216 
1219 
1220 PLAYERC_EXPORT int playerc_blackboard_set_string(playerc_blackboard_t *device, const char* key, const char* group, const char* value);
1221 
1222 PLAYERC_EXPORT int playerc_blackboard_set_int(playerc_blackboard_t *device, const char* key, const char* group, const int value);
1223 
1224 PLAYERC_EXPORT int playerc_blackboard_set_double(playerc_blackboard_t *device, const char* key, const char* group, const double value);
1225 
1228 /**************************************************************************/
1239 typedef struct
1240 {
1243 
1244  uint32_t enabled;
1245  double duty_cycle;
1246  double period;
1247  uint8_t red, green, blue;
1249 
1250 
1252 PLAYERC_EXPORT playerc_blinkenlight_t *playerc_blinkenlight_create(playerc_client_t *client, int index);
1253 
1255 PLAYERC_EXPORT void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device);
1256 
1258 PLAYERC_EXPORT int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access);
1259 
1261 PLAYERC_EXPORT int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device);
1262 
1264 PLAYERC_EXPORT int playerc_blinkenlight_enable( playerc_blinkenlight_t *device,
1265  uint32_t enable );
1266 
1268 PLAYERC_EXPORT int playerc_blinkenlight_color( playerc_blinkenlight_t *device,
1269  uint32_t id,
1270  uint8_t red,
1271  uint8_t green,
1272  uint8_t blue );
1275 PLAYERC_EXPORT int playerc_blinkenlight_blink( playerc_blinkenlight_t *device,
1276  uint32_t id,
1277  float period,
1278  float duty_cycle );
1281 /***************************************************************************/
1293 
1295 typedef struct
1296 {
1299 
1301  unsigned int width, height;
1302 
1304  unsigned int blobs_count;
1305  playerc_blobfinder_blob_t *blobs;
1306 
1308 
1309 
1311 PLAYERC_EXPORT playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
1312 
1314 PLAYERC_EXPORT void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
1315 
1317 PLAYERC_EXPORT int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
1318 
1320 PLAYERC_EXPORT int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
1321 
1322 
1324 /**************************************************************************/
1325 
1326 
1327 /**************************************************************************/
1338 typedef struct
1339 {
1342 
1345 
1350 
1353 
1355  uint8_t *bumpers;
1356 
1358 
1359 
1361 PLAYERC_EXPORT playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
1362 
1364 PLAYERC_EXPORT void playerc_bumper_destroy(playerc_bumper_t *device);
1365 
1367 PLAYERC_EXPORT int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
1368 
1370 PLAYERC_EXPORT int playerc_bumper_unsubscribe(playerc_bumper_t *device);
1371 
1378 PLAYERC_EXPORT int playerc_bumper_get_geom(playerc_bumper_t *device);
1379 
1380 
1382 /***************************************************************************/
1383 
1384 
1385 /***************************************************************************/
1395 typedef struct
1396 {
1399 
1401  int width, height;
1402 
1404  int bpp;
1405 
1407  int format;
1408 
1412  int fdiv;
1413 
1416 
1419 
1424  uint8_t *image;
1425 
1427 
1428 
1430 PLAYERC_EXPORT playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
1431 
1433 PLAYERC_EXPORT void playerc_camera_destroy(playerc_camera_t *device);
1434 
1436 PLAYERC_EXPORT int playerc_camera_subscribe(playerc_camera_t *device, int access);
1437 
1439 PLAYERC_EXPORT int playerc_camera_unsubscribe(playerc_camera_t *device);
1440 
1442 PLAYERC_EXPORT void playerc_camera_decompress(playerc_camera_t *device);
1443 
1445 PLAYERC_EXPORT void playerc_camera_save(playerc_camera_t *device, const char *filename);
1446 
1448 /**************************************************************************/
1449 
1450 
1451 /**************************************************************************/
1461 typedef struct
1462 {
1465 
1466  /*/ The number of valid digital inputs.*/
1467  uint8_t count;
1468 
1469  /*/ A bitfield of the current digital inputs.*/
1470  uint32_t digin;
1471 
1472 } playerc_dio_t;
1473 
1474 
1476 PLAYERC_EXPORT playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
1477 
1479 PLAYERC_EXPORT void playerc_dio_destroy(playerc_dio_t *device);
1480 
1482 PLAYERC_EXPORT int playerc_dio_subscribe(playerc_dio_t *device, int access);
1483 
1485 PLAYERC_EXPORT int playerc_dio_unsubscribe(playerc_dio_t *device);
1486 
1488 PLAYERC_EXPORT int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
1489 
1490 
1492 /***************************************************************************/
1493 
1494 
1495 /***************************************************************************/
1510 typedef struct
1511 {
1514 
1520 
1523  player_fiducial_item_t *fiducials;
1524 
1526 
1527 
1529 PLAYERC_EXPORT playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
1530 
1532 PLAYERC_EXPORT void playerc_fiducial_destroy(playerc_fiducial_t *device);
1533 
1535 PLAYERC_EXPORT int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
1536 
1538 PLAYERC_EXPORT int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
1539 
1546 PLAYERC_EXPORT int playerc_fiducial_get_geom(playerc_fiducial_t *device);
1547 
1548 
1550 /**************************************************************************/
1551 
1552 /***************************************************************************/
1561 typedef struct
1562 {
1565 
1567  double utc_time;
1568 
1572  double lat, lon;
1573 
1576  double alt;
1577 
1579  double utm_e, utm_n;
1580 
1582  double hdop;
1583 
1585  double vdop;
1586 
1588  double err_horz, err_vert;
1589 
1591  int quality;
1592 
1595 
1596 } playerc_gps_t;
1597 
1598 
1600 PLAYERC_EXPORT playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
1601 
1603 PLAYERC_EXPORT void playerc_gps_destroy(playerc_gps_t *device);
1604 
1606 PLAYERC_EXPORT int playerc_gps_subscribe(playerc_gps_t *device, int access);
1607 
1609 PLAYERC_EXPORT int playerc_gps_unsubscribe(playerc_gps_t *device);
1610 
1611 
1613 /**************************************************************************/
1614 
1615 /***************************************************************************/
1625 typedef struct
1626 {
1629 
1632 
1634 
1635 
1637 PLAYERC_EXPORT playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
1638 
1640 PLAYERC_EXPORT void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
1641 
1643 PLAYERC_EXPORT int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
1644 
1646 PLAYERC_EXPORT int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
1647 
1649 PLAYERC_EXPORT int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
1650  player_color_t col );
1651 
1653 PLAYERC_EXPORT int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
1654  player_point_2d_t pts[],
1655  int count );
1656 
1658 PLAYERC_EXPORT int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
1659  player_point_2d_t pts[],
1660  int count );
1661 
1663 PLAYERC_EXPORT int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
1664  player_point_2d_t pts[],
1665  int count,
1666  int filled,
1667  player_color_t fill_color );
1668 
1670 PLAYERC_EXPORT int playerc_graphics2d_clear(playerc_graphics2d_t *device );
1671 
1672 
1675 /***************************************************************************/
1685 typedef struct
1686 {
1689 
1692 
1694 
1695 
1697 PLAYERC_EXPORT playerc_graphics3d_t *playerc_graphics3d_create(playerc_client_t *client, int index);
1698 
1700 PLAYERC_EXPORT void playerc_graphics3d_destroy(playerc_graphics3d_t *device);
1701 
1703 PLAYERC_EXPORT int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
1704 
1706 PLAYERC_EXPORT int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device);
1707 
1709 PLAYERC_EXPORT int playerc_graphics3d_setcolor(playerc_graphics3d_t *device,
1710  player_color_t col );
1711 
1713 PLAYERC_EXPORT int playerc_graphics3d_draw(playerc_graphics3d_t *device,
1715  player_point_3d_t pts[],
1716  int count );
1717 
1719 PLAYERC_EXPORT int playerc_graphics3d_clear(playerc_graphics3d_t *device );
1720 
1722 PLAYERC_EXPORT int playerc_graphics3d_translate(playerc_graphics3d_t *device,
1723  double x, double y, double z );
1724 
1725 
1727 PLAYERC_EXPORT int playerc_graphics3d_rotate( playerc_graphics3d_t *device,
1728  double a, double x, double y, double z );
1731 /***************************************************************************/
1741 typedef struct
1742 {
1745 
1753  player_bbox3d_t outer_size;
1754  player_bbox3d_t inner_size;
1756  uint8_t num_beams;
1758  uint8_t capacity;
1759 
1763  uint8_t state;
1765  uint32_t beams;
1767  uint8_t stored;
1769 
1771 PLAYERC_EXPORT playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
1772 
1774 PLAYERC_EXPORT void playerc_gripper_destroy(playerc_gripper_t *device);
1775 
1777 PLAYERC_EXPORT int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
1778 
1780 PLAYERC_EXPORT int playerc_gripper_unsubscribe(playerc_gripper_t *device);
1781 
1783 PLAYERC_EXPORT int playerc_gripper_open_cmd(playerc_gripper_t *device);
1784 
1786 PLAYERC_EXPORT int playerc_gripper_close_cmd(playerc_gripper_t *device);
1787 
1789 PLAYERC_EXPORT int playerc_gripper_stop_cmd(playerc_gripper_t *device);
1790 
1792 PLAYERC_EXPORT int playerc_gripper_store_cmd(playerc_gripper_t *device);
1793 
1795 PLAYERC_EXPORT int playerc_gripper_retrieve_cmd(playerc_gripper_t *device);
1796 
1799 PLAYERC_EXPORT void playerc_gripper_printout(playerc_gripper_t *device, const char* prefix);
1800 
1805 PLAYERC_EXPORT int playerc_gripper_get_geom(playerc_gripper_t *device);
1806 
1808 /**************************************************************************/
1809 
1810 /***************************************************************************/
1824 typedef struct
1825 {
1835 
1836 
1838 PLAYERC_EXPORT playerc_health_t *playerc_health_create(playerc_client_t *client, int index);
1839 
1841 PLAYERC_EXPORT void playerc_health_destroy(playerc_health_t *device);
1842 
1844 PLAYERC_EXPORT int playerc_health_subscribe(playerc_health_t *device, int access);
1845 
1847 PLAYERC_EXPORT int playerc_health_unsubscribe(playerc_health_t *device);
1848 
1849 
1851 /***************************************************************************/
1852 
1853 
1854 /***************************************************************************/
1865 typedef struct
1866 {
1869 
1870  /* data*/
1871  player_ir_data_t data;
1872 
1873  /* config*/
1874  player_ir_pose_t poses;
1875 
1876 } playerc_ir_t;
1877 
1878 
1880 PLAYERC_EXPORT playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
1881 
1883 PLAYERC_EXPORT void playerc_ir_destroy(playerc_ir_t *device);
1884 
1886 PLAYERC_EXPORT int playerc_ir_subscribe(playerc_ir_t *device, int access);
1887 
1889 PLAYERC_EXPORT int playerc_ir_unsubscribe(playerc_ir_t *device);
1890 
1897 PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device);
1898 
1899 
1901 /***************************************************************************/
1902 
1903 
1904 /***************************************************************************/
1914 typedef struct
1915 {
1918  int32_t axes_count;
1919  int32_t pos[8];
1920  uint32_t buttons;
1921  int * axes_max;
1922  int * axes_min;
1923  double * scale_pos;
1924 
1925 
1927 
1928 
1930 PLAYERC_EXPORT playerc_joystick_t *playerc_joystick_create(playerc_client_t *client, int index);
1931 
1933 PLAYERC_EXPORT void playerc_joystick_destroy(playerc_joystick_t *device);
1934 
1936 PLAYERC_EXPORT int playerc_joystick_subscribe(playerc_joystick_t *device, int access);
1937 
1939 PLAYERC_EXPORT int playerc_joystick_unsubscribe(playerc_joystick_t *device);
1940 
1942 /**************************************************************************/
1943 
1944 
1945 /***************************************************************************/
1959 typedef struct
1960 {
1963 
1967  double pose[3];
1968  double size[2];
1969 
1971  double robot_pose[3];
1972 
1975 
1978 
1980  double scan_start;
1981 
1983  double scan_res;
1984 
1986  double range_res;
1987 
1989  double max_range;
1990 
1993 
1995  double *ranges;
1996 
1998  double (*scan)[2];
1999 
2002 
2007 
2009  int scan_id;
2010 
2013 
2017  double min_right;
2018 
2022  double min_left;
2023 } playerc_laser_t;
2024 
2025 
2027 PLAYERC_EXPORT playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
2028 
2030 PLAYERC_EXPORT void playerc_laser_destroy(playerc_laser_t *device);
2031 
2033 PLAYERC_EXPORT int playerc_laser_subscribe(playerc_laser_t *device, int access);
2034 
2036 PLAYERC_EXPORT int playerc_laser_unsubscribe(playerc_laser_t *device);
2037 
2060 PLAYERC_EXPORT int playerc_laser_set_config(playerc_laser_t *device,
2061  double min_angle, double max_angle,
2062  double resolution,
2063  double range_res,
2064  unsigned char intensity,
2065  double scanning_frequency);
2066 
2089 PLAYERC_EXPORT int playerc_laser_get_config(playerc_laser_t *device,
2090  double *min_angle,
2091  double *max_angle,
2092  double *resolution,
2093  double *range_res,
2094  unsigned char *intensity,
2095  double *scanning_frequency);
2096 
2103 PLAYERC_EXPORT int playerc_laser_get_geom(playerc_laser_t *device);
2104 
2109 PLAYERC_EXPORT int playerc_laser_get_id (playerc_laser_t *device);
2110 
2113 PLAYERC_EXPORT void playerc_laser_printout( playerc_laser_t * device,
2114  const char* prefix );
2115 
2117 /**************************************************************************/
2118 
2119 
2131 typedef struct
2132 {
2135 
2136  player_limb_data_t data;
2138 } playerc_limb_t;
2139 
2141 PLAYERC_EXPORT playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
2142 
2144 PLAYERC_EXPORT void playerc_limb_destroy(playerc_limb_t *device);
2145 
2147 PLAYERC_EXPORT int playerc_limb_subscribe(playerc_limb_t *device, int access);
2148 
2150 PLAYERC_EXPORT int playerc_limb_unsubscribe(playerc_limb_t *device);
2151 
2154 PLAYERC_EXPORT int playerc_limb_get_geom(playerc_limb_t *device);
2155 
2157 PLAYERC_EXPORT int playerc_limb_home_cmd(playerc_limb_t *device);
2158 
2160 PLAYERC_EXPORT int playerc_limb_stop_cmd(playerc_limb_t *device);
2161 
2163 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);
2164 
2167 PLAYERC_EXPORT int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
2168 
2171 PLAYERC_EXPORT int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
2172 
2176 PLAYERC_EXPORT int playerc_limb_power(playerc_limb_t *device, uint32_t enable);
2177 
2179 PLAYERC_EXPORT int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable);
2180 
2182 PLAYERC_EXPORT int playerc_limb_speed_config(playerc_limb_t *device, float speed);
2183 
2185 /**************************************************************************/
2186 
2187 
2188 /***************************************************************************/
2206 {
2207  double pose[3];
2208  double weight;
2210 
2211 
2213 typedef struct
2214 {
2217 
2219  int map_size_x, map_size_y;
2220 
2222  double map_scale;
2223 
2225  int map_tile_x, map_tile_y;
2226 
2228  int8_t *map_cells;
2229 
2232 
2235 
2238  player_localize_hypoth_t *hypoths;
2239 
2240  double mean[3];
2241  double variance;
2242  int num_particles;
2243  playerc_localize_particle_t *particles;
2244 
2246 
2247 
2249 PLAYERC_EXPORT playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
2250 
2252 PLAYERC_EXPORT void playerc_localize_destroy(playerc_localize_t *device);
2253 
2255 PLAYERC_EXPORT int playerc_localize_subscribe(playerc_localize_t *device, int access);
2256 
2258 PLAYERC_EXPORT int playerc_localize_unsubscribe(playerc_localize_t *device);
2259 
2261 PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3]);
2262 
2265 PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device);
2266 
2268 /**************************************************************************/
2269 
2270 
2271 /***************************************************************************/
2281 typedef struct
2282 {
2285 
2288  int type;
2289 
2292  int state;
2293 } playerc_log_t;
2294 
2295 
2297 PLAYERC_EXPORT playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
2298 
2300 PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device);
2301 
2303 PLAYERC_EXPORT int playerc_log_subscribe(playerc_log_t *device, int access);
2304 
2306 PLAYERC_EXPORT int playerc_log_unsubscribe(playerc_log_t *device);
2307 
2309 PLAYERC_EXPORT int playerc_log_set_write_state(playerc_log_t* device, int state);
2310 
2312 PLAYERC_EXPORT int playerc_log_set_read_state(playerc_log_t* device, int state);
2313 
2315 PLAYERC_EXPORT int playerc_log_set_read_rewind(playerc_log_t* device);
2316 
2322 PLAYERC_EXPORT int playerc_log_get_state(playerc_log_t* device);
2323 
2325 PLAYERC_EXPORT int playerc_log_set_filename(playerc_log_t* device, const char* fname);
2326 
2327 
2331 /***************************************************************************/
2341 typedef struct
2342 {
2345 
2347  double resolution;
2348 
2350  int width, height;
2351 
2353  double origin[2];
2354 
2356  char* cells;
2357 
2360  double vminx, vminy, vmaxx, vmaxy;
2361  int num_segments;
2362  player_segment_t* segments;
2363 } playerc_map_t;
2364 
2367 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
2368 
2370 PLAYERC_EXPORT playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
2371 
2373 PLAYERC_EXPORT void playerc_map_destroy(playerc_map_t *device);
2374 
2376 PLAYERC_EXPORT int playerc_map_subscribe(playerc_map_t *device, int access);
2377 
2379 PLAYERC_EXPORT int playerc_map_unsubscribe(playerc_map_t *device);
2380 
2382 PLAYERC_EXPORT int playerc_map_get_map(playerc_map_t* device);
2383 
2385 PLAYERC_EXPORT int playerc_map_get_vector(playerc_map_t* device);
2386 
2388 /**************************************************************************/
2389 
2398 typedef struct
2399 {
2403  uint32_t srid;
2407  uint32_t layers_count;
2413  playerwkbprocessor_t wkbprocessor;
2414 
2416 
2418 PLAYERC_EXPORT playerc_vectormap_t *playerc_vectormap_create(playerc_client_t *client, int index);
2419 
2421 PLAYERC_EXPORT void playerc_vectormap_destroy(playerc_vectormap_t *device);
2422 
2424 PLAYERC_EXPORT int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access);
2425 
2427 PLAYERC_EXPORT int playerc_vectormap_unsubscribe(playerc_vectormap_t *device);
2428 
2430 PLAYERC_EXPORT int playerc_vectormap_get_map_info(playerc_vectormap_t* device);
2431 
2433 PLAYERC_EXPORT int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index);
2434 
2436 PLAYERC_EXPORT int playerc_vectormap_write_layer(playerc_vectormap_t *device, const player_vectormap_layer_data_t * data);
2437 
2439 PLAYERC_EXPORT void playerc_vectormap_cleanup(playerc_vectormap_t *device);
2440 
2443 PLAYERC_EXPORT uint8_t * playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2444 PLAYERC_EXPORT size_t playerc_vectormap_get_feature_data_count(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2445 
2448 /***************************************************************************/
2459 typedef struct
2460 {
2463 
2466 
2468  uint8_t *data;
2470 
2472 PLAYERC_EXPORT playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
2473 
2475 PLAYERC_EXPORT void playerc_opaque_destroy(playerc_opaque_t *device);
2476 
2478 PLAYERC_EXPORT int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
2479 
2481 PLAYERC_EXPORT int playerc_opaque_unsubscribe(playerc_opaque_t *device);
2482 
2484 PLAYERC_EXPORT int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
2485 
2492 PLAYERC_EXPORT int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply);
2493 
2495 /**************************************************************************/
2496 
2497 
2498 /***************************************************************************/
2508 typedef struct
2509 {
2512 
2515 
2518 
2520  double px, py, pa;
2521 
2523  double gx, gy, ga;
2524 
2526  double wx, wy, wa;
2527 
2532 
2535 
2538  double (*waypoints)[3];
2539 
2541 
2543 PLAYERC_EXPORT playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
2544 
2546 PLAYERC_EXPORT void playerc_planner_destroy(playerc_planner_t *device);
2547 
2549 PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access);
2550 
2552 PLAYERC_EXPORT int playerc_planner_unsubscribe(playerc_planner_t *device);
2553 
2555 PLAYERC_EXPORT int playerc_planner_set_cmd_pose(playerc_planner_t *device,
2556  double gx, double gy, double ga);
2557 
2564 PLAYERC_EXPORT int playerc_planner_get_waypoints(playerc_planner_t *device);
2565 
2571 PLAYERC_EXPORT int playerc_planner_enable(playerc_planner_t *device, int state);
2572 
2574 /**************************************************************************/
2575 
2576 /***************************************************************************/
2587 typedef struct
2588 {
2591 
2595  double pose[3];
2596  double size[2];
2597 
2599  double pos;
2600 
2602  double vel;
2603 
2605  int stall;
2606 
2618  int status;
2619 
2621 
2624  int index);
2625 
2627 PLAYERC_EXPORT void playerc_position1d_destroy(playerc_position1d_t *device);
2628 
2630 PLAYERC_EXPORT int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
2631 
2633 PLAYERC_EXPORT int playerc_position1d_unsubscribe(playerc_position1d_t *device);
2634 
2636 PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable);
2637 
2640 PLAYERC_EXPORT int playerc_position1d_get_geom(playerc_position1d_t *device);
2641 
2643 PLAYERC_EXPORT int playerc_position1d_set_cmd_vel(playerc_position1d_t *device,
2644  double vel, int state);
2645 
2649 PLAYERC_EXPORT int playerc_position1d_set_cmd_pos(playerc_position1d_t *device,
2650  double pos, int state);
2651 
2657  double pos, double vel, int state);
2658 
2660 PLAYERC_EXPORT int playerc_position1d_set_odom(playerc_position1d_t *device,
2661  double odom);
2662 
2664 /**************************************************************************/
2665 
2666 
2667 /***************************************************************************/
2681 typedef struct
2682 {
2685 
2689  double pose[3];
2690  double size[2];
2691 
2693  double px, py, pa;
2694 
2696  double vx, vy, va;
2697 
2699  int stall;
2700 
2702 
2705  int index);
2706 
2708 PLAYERC_EXPORT void playerc_position2d_destroy(playerc_position2d_t *device);
2709 
2711 PLAYERC_EXPORT int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
2712 
2714 PLAYERC_EXPORT int playerc_position2d_unsubscribe(playerc_position2d_t *device);
2715 
2717 PLAYERC_EXPORT int playerc_position2d_enable(playerc_position2d_t *device, int enable);
2718 
2721 PLAYERC_EXPORT int playerc_position2d_get_geom(playerc_position2d_t *device);
2722 
2727 PLAYERC_EXPORT int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
2728  double vx, double vy, double va, int state);
2729 
2732  player_pose2d_t pos,
2733  player_pose2d_t vel,
2734  int state);
2735 
2741  double vx, double vy, double pa, int state);
2742 
2743 
2744 
2747 PLAYERC_EXPORT int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
2748  double gx, double gy, double ga, int state);
2749 
2751 PLAYERC_EXPORT int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
2752  double vx, double a);
2753 
2755 PLAYERC_EXPORT int playerc_position2d_set_odom(playerc_position2d_t *device,
2756  double ox, double oy, double oa);
2757 
2759 /**************************************************************************/
2760 
2761 /***************************************************************************/
2776 typedef struct
2777 {
2780 
2784  double pose[3];
2785  double size[2];
2786 
2788  double pos_x, pos_y, pos_z;
2789 
2791  double pos_roll, pos_pitch, pos_yaw;
2792 
2794  double vel_x, vel_y, vel_z;
2795 
2797  double vel_roll, vel_pitch, vel_yaw;
2798 
2800  int stall;
2801 
2803 
2804 
2807  int index);
2808 
2810 PLAYERC_EXPORT void playerc_position3d_destroy(playerc_position3d_t *device);
2811 
2813 PLAYERC_EXPORT int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
2814 
2816 PLAYERC_EXPORT int playerc_position3d_unsubscribe(playerc_position3d_t *device);
2817 
2819 PLAYERC_EXPORT int playerc_position3d_enable(playerc_position3d_t *device, int enable);
2820 
2823 PLAYERC_EXPORT int playerc_position3d_get_geom(playerc_position3d_t *device);
2824 
2829 PLAYERC_EXPORT int playerc_position3d_set_velocity(playerc_position3d_t *device,
2830  double vx, double vy, double vz,
2831  double vr, double vp, double vt,
2832  int state);
2833 
2835 PLAYERC_EXPORT int playerc_position3d_set_speed(playerc_position3d_t *device,
2836  double vx, double vy, double vz, int state);
2837 
2840 PLAYERC_EXPORT int playerc_position3d_set_pose(playerc_position3d_t *device,
2841  double gx, double gy, double gz,
2842  double gr, double gp, double gt);
2843 
2844 
2847  player_pose3d_t pos,
2848  player_pose3d_t vel);
2849 
2851 PLAYERC_EXPORT int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
2852  double gx, double gy, double gz);
2853 
2855 PLAYERC_EXPORT int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
2856 
2858 PLAYERC_EXPORT int playerc_position3d_set_odom(playerc_position3d_t *device,
2859  double ox, double oy, double oz,
2860  double oroll, double opitch, double oyaw);
2861 
2863 PLAYERC_EXPORT int playerc_position3d_reset_odom(playerc_position3d_t *device);
2864 
2866 /**************************************************************************/
2867 
2868 
2869 /***************************************************************************/
2880 typedef struct
2881 {
2884 
2887  int valid;
2888 
2890  double charge;
2891 
2893  double percent;
2894 
2896  double joules;
2897 
2900  double watts;
2901 
2904 
2905 } playerc_power_t;
2906 
2907 
2909 PLAYERC_EXPORT playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
2910 
2912 PLAYERC_EXPORT void playerc_power_destroy(playerc_power_t *device);
2913 
2915 PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access);
2916 
2918 PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device);
2919 
2920 
2922 /**************************************************************************/
2923 
2924 
2925 
2926 /***************************************************************************/
2937 typedef struct
2938 {
2941 
2945  double pan, tilt;
2946 
2948  double zoom;
2949 
2951  int status;
2952 } playerc_ptz_t;
2953 
2954 
2956 PLAYERC_EXPORT playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
2957 
2959 PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device);
2960 
2962 PLAYERC_EXPORT int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
2963 
2965 PLAYERC_EXPORT int playerc_ptz_unsubscribe(playerc_ptz_t *device);
2966 
2975 PLAYERC_EXPORT int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
2976 
2982 PLAYERC_EXPORT int playerc_ptz_query_status(playerc_ptz_t *device);
2983 
2994 PLAYERC_EXPORT int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
2995  double panspeed, double tiltspeed);
2996 
3004 PLAYERC_EXPORT int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
3005 
3007 /**************************************************************************/
3008 
3009 /***************************************************************************/
3019 typedef struct
3020 {
3023 
3025  uint32_t element_count;
3026 
3028  double min_angle;
3030  double max_angle;
3032  double angular_res;
3035  double min_range;
3037  double max_range;
3039  double range_res;
3041  double frequency;
3042 
3047  player_bbox3d_t device_size;
3052  player_bbox3d_t *element_sizes;
3053 
3055  uint32_t ranges_count;
3057  double *ranges;
3058 
3064  double *intensities;
3065 
3067  uint32_t bearings_count;
3070  double *bearings;
3071 
3073  uint32_t points_count;
3076 
3078 
3080 PLAYERC_EXPORT playerc_ranger_t *playerc_ranger_create(playerc_client_t *client, int index);
3081 
3083 PLAYERC_EXPORT void playerc_ranger_destroy(playerc_ranger_t *device);
3084 
3086 PLAYERC_EXPORT int playerc_ranger_subscribe(playerc_ranger_t *device, int access);
3087 
3089 PLAYERC_EXPORT int playerc_ranger_unsubscribe(playerc_ranger_t *device);
3090 
3095 PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device);
3096 
3100 PLAYERC_EXPORT int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value);
3101 
3105 PLAYERC_EXPORT int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value);
3106 
3115 PLAYERC_EXPORT int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle,
3116  double max_angle, double angular_res,
3117  double min_range, double max_range,
3118  double range_res, double frequency);
3119 
3128 PLAYERC_EXPORT int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle,
3129  double *max_angle, double *angular_res,
3130  double *min_range, double *max_range,
3131  double *range_res, double *frequency);
3132 
3134 /**************************************************************************/
3135 
3136 /***************************************************************************/
3147 typedef struct
3148 {
3151 
3154 
3158 
3161 
3163  double *scan;
3164 
3165 } playerc_sonar_t;
3166 
3167 
3169 PLAYERC_EXPORT playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
3170 
3172 PLAYERC_EXPORT void playerc_sonar_destroy(playerc_sonar_t *device);
3173 
3175 PLAYERC_EXPORT int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
3176 
3178 PLAYERC_EXPORT int playerc_sonar_unsubscribe(playerc_sonar_t *device);
3179 
3185 PLAYERC_EXPORT int playerc_sonar_get_geom(playerc_sonar_t *device);
3186 
3188 /**************************************************************************/
3189 
3190 /***************************************************************************/
3202 typedef struct
3203 {
3205  uint8_t mac[32];
3206 
3208  uint8_t ip[32];
3209 
3211  uint8_t essid[32];
3212 
3214  int mode;
3215 
3217  int encrypt;
3218 
3220  double freq;
3221 
3223  int qual, level, noise;
3224 
3226 
3227 
3229 typedef struct
3230 {
3233 
3236  int link_count;
3237  char ip[32];
3238 } playerc_wifi_t;
3239 
3240 
3242 PLAYERC_EXPORT playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
3243 
3245 PLAYERC_EXPORT void playerc_wifi_destroy(playerc_wifi_t *device);
3246 
3248 PLAYERC_EXPORT int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
3249 
3251 PLAYERC_EXPORT int playerc_wifi_unsubscribe(playerc_wifi_t *device);
3252 
3254 PLAYERC_EXPORT playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
3255 
3256 
3258 /**************************************************************************/
3259 
3260 /***************************************************************************/
3272 typedef struct
3273 {
3276 
3278 
3279 
3281 PLAYERC_EXPORT playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
3282 
3284 PLAYERC_EXPORT void playerc_simulation_destroy(playerc_simulation_t *device);
3285 
3287 PLAYERC_EXPORT int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
3288 
3290 PLAYERC_EXPORT int playerc_simulation_unsubscribe(playerc_simulation_t *device);
3291 
3293 PLAYERC_EXPORT int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
3294  double gx, double gy, double ga);
3295 
3297 PLAYERC_EXPORT int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
3298  double *x, double *y, double *a);
3299 
3301 PLAYERC_EXPORT int playerc_simulation_set_pose3d(playerc_simulation_t *device, char* name,
3302  double gx, double gy, double gz,
3303  double groll, double gpitch, double gyaw);
3304 
3306 PLAYERC_EXPORT int playerc_simulation_get_pose3d(playerc_simulation_t *device, char* identifier,
3307  double *x, double *y, double *z,
3308  double *roll, double *pitch, double *yaw, double *time);
3309 
3311 PLAYERC_EXPORT int playerc_simulation_set_property(playerc_simulation_t *device,
3312  char* name,
3313  char* property,
3314  void* value,
3315  size_t value_len);
3316 
3318 PLAYERC_EXPORT int playerc_simulation_get_property(playerc_simulation_t *device,
3319  char* name,
3320  char* property,
3321  void* value,
3322  size_t value_len);
3323 
3325 PLAYERC_EXPORT int playerc_simulation_pause(playerc_simulation_t *device );
3326 
3328 PLAYERC_EXPORT int playerc_simulation_reset(playerc_simulation_t *device );
3329 
3331 PLAYERC_EXPORT int playerc_simulation_save(playerc_simulation_t *device );
3332 
3333 
3335 /***************************************************************************/
3336 
3337 
3338 /**************************************************************************/
3348 typedef struct
3349 {
3353 
3354 
3356 PLAYERC_EXPORT playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
3357 
3359 PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device);
3360 
3362 PLAYERC_EXPORT int playerc_speech_subscribe(playerc_speech_t *device, int access);
3363 
3365 PLAYERC_EXPORT int playerc_speech_unsubscribe(playerc_speech_t *device);
3366 
3368 PLAYERC_EXPORT int playerc_speech_say (playerc_speech_t *device, char *);
3369 
3370 
3372 /***************************************************************************/
3373 
3374 /**************************************************************************/
3384 typedef struct
3385 {
3388 
3389  char *rawText;
3390  /* Just estimating that no more than 20 words will be spoken between updates.
3391  Assuming that the longest word is <= 30 characters.*/
3392  char **words;
3393  int wordCount;
3395 
3396 
3399 
3402 
3404 PLAYERC_EXPORT int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access);
3405 
3408 
3410 /***************************************************************************/
3411 
3412 /**************************************************************************/
3422 typedef struct
3423 {
3425  uint32_t type;
3427  uint32_t guid_count;
3429  uint8_t *guid;
3431 
3433 typedef struct
3434 {
3437 
3439  uint16_t tags_count;
3440 
3443 } playerc_rfid_t;
3444 
3445 
3447 PLAYERC_EXPORT playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
3448 
3450 PLAYERC_EXPORT void playerc_rfid_destroy(playerc_rfid_t *device);
3451 
3453 PLAYERC_EXPORT int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
3454 
3456 PLAYERC_EXPORT int playerc_rfid_unsubscribe(playerc_rfid_t *device);
3457 
3459 /***************************************************************************/
3460 
3461 /**************************************************************************/
3472 
3474 typedef struct
3475 {
3478 
3480  uint16_t points_count;
3481 
3483  playerc_pointcloud3d_element_t *points;
3485 
3486 
3488 PLAYERC_EXPORT playerc_pointcloud3d_t *playerc_pointcloud3d_create (playerc_client_t *client, int index);
3489 
3491 PLAYERC_EXPORT void playerc_pointcloud3d_destroy (playerc_pointcloud3d_t *device);
3492 
3494 PLAYERC_EXPORT int playerc_pointcloud3d_subscribe (playerc_pointcloud3d_t *device, int access);
3495 
3497 PLAYERC_EXPORT int playerc_pointcloud3d_unsubscribe (playerc_pointcloud3d_t *device);
3498 
3500 /***************************************************************************/
3501 
3502 /**************************************************************************/
3512 
3514 typedef struct
3515 {
3518 
3519  /* Left channel image */
3520  playerc_camera_t left_channel;
3521  /* Right channel image */
3522  playerc_camera_t right_channel;
3523 
3524  /* Disparity image */
3525  playerc_camera_t disparity;
3526 
3527  /* 3-D stereo point cloud */
3528  uint32_t points_count;
3529  playerc_pointcloud3d_stereo_element_t *points;
3530 // player_pointcloud3d_data_t pointcloud;
3532 
3533 
3535 PLAYERC_EXPORT playerc_stereo_t *playerc_stereo_create (playerc_client_t *client, int index);
3536 
3538 PLAYERC_EXPORT void playerc_stereo_destroy (playerc_stereo_t *device);
3539 
3541 PLAYERC_EXPORT int playerc_stereo_subscribe (playerc_stereo_t *device, int access);
3542 
3544 PLAYERC_EXPORT int playerc_stereo_unsubscribe (playerc_stereo_t *device);
3545 
3547 /***************************************************************************/
3548 
3549 /**************************************************************************/
3559 typedef struct
3560 {
3563 
3566  player_pose3d_t vel;
3567  player_pose3d_t acc;
3568 
3571 
3573  float q0, q1, q2, q3;
3574 } playerc_imu_t;
3575 
3577 PLAYERC_EXPORT playerc_imu_t *playerc_imu_create (playerc_client_t *client, int index);
3578 
3580 PLAYERC_EXPORT void playerc_imu_destroy (playerc_imu_t *device);
3581 
3583 PLAYERC_EXPORT int playerc_imu_subscribe (playerc_imu_t *device, int access);
3584 
3586 PLAYERC_EXPORT int playerc_imu_unsubscribe (playerc_imu_t *device);
3587 
3589 PLAYERC_EXPORT int playerc_imu_datatype (playerc_imu_t *device, int value);
3590 
3592 PLAYERC_EXPORT int playerc_imu_reset_orientation (playerc_imu_t *device, int value);
3593 
3595 /***************************************************************************/
3596 
3597 /**************************************************************************/
3610 typedef struct
3611 {
3614 
3616  uint32_t node_type;
3618  uint32_t node_id;
3620  uint32_t node_parent_id;
3623 } playerc_wsn_t;
3624 
3625 
3627 PLAYERC_EXPORT playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
3628 
3630 PLAYERC_EXPORT void playerc_wsn_destroy(playerc_wsn_t *device);
3631 
3633 PLAYERC_EXPORT int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
3634 
3636 PLAYERC_EXPORT int playerc_wsn_unsubscribe(playerc_wsn_t *device);
3637 
3639 PLAYERC_EXPORT int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
3640  int group_id, int devnr, int state);
3641 
3643 PLAYERC_EXPORT int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
3644  int value);
3645 
3647 PLAYERC_EXPORT int playerc_wsn_datatype(playerc_wsn_t *device, int value);
3648 
3650 PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
3651  double frequency);
3652 
3654 /***************************************************************************/
3655 
3656 #ifdef __cplusplus
3657 }
3658 #endif
3659 
3660 #endif
Fiducial finder data.
Definition: playerc.h:1510
Structure describing the WSN node's data packet.
Definition: player_interfaces.h:4335
Opaque device data.
Definition: playerc.h:2459
double charge
Battery charge (Volts).
Definition: playerc.h:2890
double vel_roll
Angular velocity (radians/sec).
Definition: playerc.h:2797
uint32_t node_parent_id
The ID of the WSN node's parent (if existing).
Definition: playerc.h:3620
PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device)
Get the ranger geometry.
int width
Map size, in cells.
Definition: playerc.h:2350
double * ranges
Range data [m].
Definition: playerc.h:3057
Planner device data.
Definition: playerc.h:2508
PLAYERC_EXPORT int playerc_wsn_datatype(playerc_wsn_t *device, int value)
Change the data type to RAW or converted engineering units.
Ir proxy data.
Definition: playerc.h:1865
PLAYERC_EXPORT int playerc_device_get_boolprop(playerc_device_t *device, char *property, BOOL *value)
Request a boolean property.
RFID proxy data.
Definition: playerc.h:3433
Aio proxy data.
Definition: playerc.h:929
PLAYERC_EXPORT int playerc_laser_get_id(playerc_laser_t *device)
Get the laser IDentification information.
PLAYERC_EXPORT void playerc_graphics3d_destroy(playerc_graphics3d_t *device)
Destroy a graphics3d device proxy.
PLAYERC_EXPORT int playerc_map_get_map(playerc_map_t *device)
Get the map, which is stored in the proxy.
data
Definition: player_interfaces.h:3414
double gx
Goal location (m, m, radians)
Definition: playerc.h:2523
PLAYERC_EXPORT playerc_speech_t * playerc_speech_create(playerc_client_t *client, int index)
Create a speech proxy.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1917
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1398
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_dio_subscribe(playerc_dio_t *device, int access)
Subscribe to the dio device.
Vectormap proxy.
Definition: playerc.h:2398
PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index)
Unsubscribe a device.
double alt
Altitude (meters).
Definition: playerc.h:1576
Vectormap feature data.
Definition: player.h:261
PLAYERC_EXPORT void playerc_gps_destroy(playerc_gps_t *device)
Destroy a gps proxy.
PLAYERC_EXPORT int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t *tones)
Command to play sequence of tones.
A rectangular bounding box, used to define the size of an object.
Definition: player.h:250
Generic message header.
Definition: player.h:157
Data: calibrated IMU data (PLAYER_IMU_DATA_CALIB)
Definition: player_interfaces.h:4670
Note: the structure describing the WSN node's data packet is declared in Player.
Definition: playerc.h:3610
PLAYERC_EXPORT void playerc_blackboard_destroy(playerc_blackboard_t *device)
Destroy a blackboard proxy.
#define PLAYER_MAX_DRIVER_STRING_LEN
Maximum length for a driver name.
Definition: player.h:68
struct _playerc_client_t playerc_client_t
Client object data.
PLAYERC_EXPORT int playerc_opaque_unsubscribe(playerc_opaque_t *device)
Un-subscribe from the opaque device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1513
Structure describing a single RFID tag.
Definition: playerc.h:3422
uint8_t state
The gripper's state: may be one of PLAYER_GRIPPER_STATE_OPEN, PLAYER_GRIPPER_STATE_CLOSED, PLAYER_GRIPPER_STATE_MOVING or PLAYER_GRIPPER_STATE_ERROR.
Definition: playerc.h:1763
int width
Image dimensions (pixels).
Definition: playerc.h:1401
int pending_count
The number of pending (unprocessed) sensor readings.
Definition: playerc.h:2231
int scan_count
Number of points in the scan.
Definition: playerc.h:1977
A rectangular bounding box, used to define the origin and bounds of an object.
Definition: player.h:303
double px
Odometric pose (m, m, rad).
Definition: playerc.h:2693
PLAYERC_EXPORT int playerc_position3d_reset_odom(playerc_position3d_t *device)
Reset the odometry offset.
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.
int sat_count
Number of satellites in view.
Definition: playerc.h:1594
PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device)
Destroy a log proxy.
uint32_t srid
Spatial reference identifier.
Definition: playerc.h:2403
PLAYERC_EXPORT int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char *group)
Subscribe to a group.
Localization device data.
Definition: playerc.h:2213
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3351
int image_count
Size of image data (bytes)
Definition: playerc.h:1418
player_point_2d_t * point
Scan data; x, y position (m).
Definition: playerc.h:2001
PLAYERC_EXPORT int playerc_graphics2d_clear(playerc_graphics2d_t *device)
Clear the canvas.
int state
Is logging/playback enabled? Call playerc_log_get_state() to fill it.
Definition: playerc.h:2292
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_graphics3d_clear(playerc_graphics3d_t *device)
Clear the canvas.
PLAYERC_EXPORT int playerc_position1d_subscribe(playerc_position1d_t *device, int access)
Subscribe to the position1d device.
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 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 player_actarray_actuatorgeom_t playerc_actarray_get_actuator_geom(playerc_actarray_t *device, uint32_t index)
Accessor method for the actuator geom.
player_audio_wav_t wav_data
last block of recorded data
Definition: playerc.h:1089
double watts
power currently being used (Watts).
Definition: playerc.h:2900
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_dio_unsubscribe(playerc_dio_t *device)
Un-subscribe from the dio device.
A color descriptor.
Definition: player.h:316
double err_horz
Horizontal and vertical error (meters).
Definition: playerc.h:1588
player_pointcloud3d_stereo_element_t playerc_pointcloud3d_stereo_element_t
Structure describing a single 3D pointcloud element.
Definition: playerc.h:3511
uint8_t motor_state
Reports if the actuators are off (0) or on (1)
Definition: playerc.h:999
PLAYERC_EXPORT int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value)
Request a string property.
PLAYERC_EXPORT int playerc_laser_get_geom(playerc_laser_t *device)
Get the laser geometry.
PLAYERC_EXPORT void playerc_vectormap_cleanup(playerc_vectormap_t *device)
Clean up the dynamically allocated memory for the vectormap.
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 void playerc_sonar_destroy(playerc_sonar_t *device)
Destroy a sonar proxy.
PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char *key, const char *group)
Unsubscribe from a key.
Actuator geometry.
Definition: player_interfaces.h:3786
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition: playerc.h:2696
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)...
PLAYERC_EXPORT int playerc_ir_subscribe(playerc_ir_t *device, int access)
Subscribe to the ir device.
PLAYERC_EXPORT int playerc_bumper_unsubscribe(playerc_bumper_t *device)
Un-subscribe from the bumper device.
PLAYERC_EXPORT int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index)
Command to play prestored sample.
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition: playerc.h:3570
PLAYERC_EXPORT void playerc_simulation_destroy(playerc_simulation_t *device)
Destroy a simulation proxy.
PLAYERC_EXPORT void playerc_pointcloud3d_destroy(playerc_pointcloud3d_t *device)
Destroy a pointcloud3d proxy.
PLAYERC_EXPORT int playerc_planner_get_waypoints(playerc_planner_t *device)
Get the list of waypoints.
PLAYERC_EXPORT void playerc_opaque_destroy(playerc_opaque_t *device)
Destroy an opaque device 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 playerc_opaque_t * playerc_opaque_create(playerc_client_t *client, int index)
Create an opaque device proxy.
uint8_t num_beams
The number of breakbeams the gripper has.
Definition: playerc.h:1756
PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device)
Destroy a speech proxy.
Structure describing the cpu.
Definition: player_interfaces.h:4572
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3150
PLAYERC_EXPORT void playerc_rfid_destroy(playerc_rfid_t *device)
Destroy a rfid proxy.
PLAYERC_EXPORT playerc_gps_t * playerc_gps_create(playerc_client_t *client, int index)
Create a gps proxy.
Structure describing the memory.
Definition: player_interfaces.h:4583
int intensity_on
Is intesity data returned.
Definition: playerc.h:1974
struct _playerc_device_t playerc_device_t
Common device info.
playerc_client_t * client
Pointer to the client proxy.
Definition: playerc.h:822
Common device info.
Definition: playerc.h:814
PLAYERC_EXPORT int playerc_audio_get_mixer_levels(playerc_audio_t *device)
Request mixer channel data result is stored in mixer_data.
pointcloud3d proxy data.
Definition: playerc.h:3474
double pos_x
Device position (m).
Definition: playerc.h:2788
PLAYERC_EXPORT int playerc_position2d_subscribe(playerc_position2d_t *device, int access)
Subscribe to the position2d device.
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...
double lat
Latitude and logitude (degrees).
Definition: playerc.h:1572
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1688
PLAYERC_EXPORT int playerc_imu_datatype(playerc_imu_t *device, int value)
Change the data type to one of the predefined data structures.
Camera proxy data.
Definition: playerc.h:1395
PLAYERC_EXPORT int playerc_laser_subscribe(playerc_laser_t *device, int access)
Subscribe to the laser device.
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 playerc_imu_t * playerc_imu_create(playerc_client_t *client, int index)
Create a imu proxy.
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 int playerc_position2d_enable(playerc_position2d_t *device, int enable)
Enable/disable the motors.
double scan_start
Start bearing of the scan (radians).
Definition: playerc.h:1980
PLAYERC_EXPORT int playerc_gripper_get_geom(playerc_gripper_t *device)
Get the gripper geometry.
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 int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device)
Add a device proxy.
double px
Current pose (m, m, radians).
Definition: playerc.h:2520
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.
int path_valid
Did the planner find a valid path?
Definition: playerc.h:2514
stereo proxy data.
Definition: playerc.h:3514
Simulation device proxy.
Definition: playerc.h:3272
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)
Speech recognition proxy data.
Definition: playerc.h:3384
PLAYERC_EXPORT int playerc_graphics2d_setcolor(playerc_graphics2d_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_ptz_subscribe(playerc_ptz_t *device, int access)
Subscribe to the ptz device.
player_pose3d_t * poses
Pose of each sonar relative to robot (m, m, radians).
Definition: playerc.h:3157
int retry_limit
How many times we'll try to reconnect after a socket error.
Definition: playerc.h:479
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_limb_destroy(playerc_limb_t *device)
Destroy a limb proxy.
PLAYERC_EXPORT int playerc_graphics3d_setcolor(playerc_graphics3d_t *device, player_color_t col)
Set the current drawing color.
uint32_t layers_count
The number of layers.
Definition: playerc.h:2407
double pan
The current ptz pan and tilt angles.
Definition: playerc.h:2945
PLAYERC_EXPORT int playerc_device_unsubscribe(playerc_device_t *device)
Unsubscribe the device.
PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[3])
Set the the robot pose (mean and covariance).
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.
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition: playerc.h:3480
PLAYERC_EXPORT int playerc_blackboard_unsubscribe(playerc_blackboard_t *device)
Un-subscribe from the blackboard device.
PLAYERC_EXPORT playerc_gripper_t * playerc_gripper_create(playerc_client_t *client, int index)
Create a gripper device proxy.
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_bumper_get_geom(playerc_bumper_t *device)
Get the bumper geometry.
PLAYERC_EXPORT int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data)
Send a generic command.
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.
int connected
Whether or not we're currently connected.
Definition: playerc.h:474
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 typedef void(* playerc_callback_fn_t)(void *data)
Typedef for proxy callback function.
Definition: playerc.h:442
PLAYERC_EXPORT int playerc_device_subscribe(playerc_device_t *device, int access)
Subscribe the device.
double scanning_frequency
Scanning frequency in Hz.
Definition: playerc.h:1992
PLAYERC_EXPORT playerc_position3d_t * playerc_position3d_create(playerc_client_t *client, int index)
Create a position3d device proxy.
PLAYERC_EXPORT playerc_planner_t * playerc_planner_create(playerc_client_t *client, int index)
Create a planner device proxy.
uint32_t bearings_count
Number of scan bearings.
Definition: playerc.h:3067
A pose in the plane.
Definition: player.h:213
PLAYERC_EXPORT int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access)
Subscribe to the blackboard device.
PLAYERC_EXPORT int playerc_client_subscribe(playerc_client_t *client, int code, int index, int access, char *drivername, size_t len)
Subscribe a device.
double * intensities
Intensity data [m].
Definition: playerc.h:3064
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition: playerc.h:1355
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam...
Definition: playerc.h:2017
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_bumper_destroy(playerc_bumper_t *device)
Destroy a bumper proxy.
PLAYERC_EXPORT int playerc_speech_subscribe(playerc_speech_t *device, int access)
Subscribe to the speech device.
PLAYERC_EXPORT playerc_fiducial_t * playerc_fiducial_create(playerc_client_t *client, int index)
Create a fiducial proxy.
PLAYERC_EXPORT int playerc_position3d_get_geom(playerc_position3d_t *device)
Get the position3d geometry.
double min_angle
Start angle of scans [rad].
Definition: playerc.h:3028
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_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2940
player_color_t color
current drawing color
Definition: playerc.h:1631
PLAYERC_EXPORT int playerc_position1d_set_odom(playerc_position1d_t *device, double odom)
Set the odometry offset.
Graphics3d device data.
Definition: playerc.h:1685
player_health_memory_t mem
The memory stats.
Definition: playerc.h:1831
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_joystick_subscribe(playerc_joystick_t *device, int access)
Subscribe to the joystick device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3436
PLAYERC_EXPORT playerc_map_t * playerc_map_create(playerc_client_t *client, int index)
Create a map proxy.
int data_count
Size of data (bytes)
Definition: playerc.h:2465
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1181
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc.h:2288
double pos
Odometric pose [m] or [rad].
Definition: playerc.h:2599
#define PLAYER_MAX_DEVICES
The maximum number of devices the server will support.
Definition: player.h:70
An angle in 3D space.
Definition: player.h:202
PLAYERC_EXPORT void playerc_blobfinder_destroy(playerc_blobfinder_t *device)
Destroy a blobfinder proxy.
double frequency
Scanning frequency [Hz].
Definition: playerc.h:3041
PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access)
Subscribe to the planner device.
PLAYERC_EXPORT int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value)
Request a double property.
int pose_count
Number of pose values.
Definition: playerc.h:1344
Power device data.
Definition: playerc.h:2880
PLAYERC_EXPORT int playerc_client_disconnect(playerc_client_t *client)
Disconnect from the server.
Blinklight proxy data.
Definition: playerc.h:1239
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.
A device address.
Definition: player.h:141
PLAYERC_EXPORT playerc_blobfinder_t * playerc_blobfinder_create(playerc_client_t *client, int index)
Create a blobfinder proxy.
PLAYERC_EXPORT int playerc_position1d_unsubscribe(playerc_position1d_t *device)
Un-subscribe from the position1d device.
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 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_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_graphics3d_subscribe(playerc_graphics3d_t *device, int access)
Subscribe to the graphics3d device.
double vel
Odometric velocity [m/s] or [rad/s].
Definition: playerc.h:2602
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1962
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2684
PLAYERC_EXPORT playerc_graphics2d_t * playerc_graphics2d_create(playerc_client_t *client, int index)
Create a graphics2d device proxy.
double resolution
Map resolution, m/cell.
Definition: playerc.h:2347
PLAYERC_EXPORT int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access)
Subscribe to the blobfinder device.
PLAYERC_EXPORT int playerc_map_get_vector(playerc_map_t *device)
Get the vector map, which is stored in the proxy.
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 void playerc_planner_destroy(playerc_planner_t *device)
Destroy a planner device proxy.
double joules
energy stored (Joules)
Definition: playerc.h:2896
int valid
status bits.
Definition: playerc.h:2887
void(* on_blackboard_event)(struct playerc_blackboard *, player_blackboard_entry_t)
Function to be called when a key is updated.
Definition: playerc.h:1183
double utc_time
UTC time (seconds since the epoch)
Definition: playerc.h:1567
PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device)
Un-subscribe from the power device.
Gripper device data.
Definition: playerc.h:1741
int map_size_x
Map dimensions (cells).
Definition: playerc.h:2219
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_device_set_dblprop(playerc_device_t *device, char *property, double value)
Set a double property.
Data: state (PLAYER_LIMB_DATA)
Definition: player_interfaces.h:4037
Structure containing a single actuator's information.
Definition: player_interfaces.h:3758
T limit(T a, T min, T max)
Limit a value to the range of min, max.
Definition: utility.h:114
Map proxy data.
Definition: playerc.h:2341
double max_range
Maximum range [m].
Definition: playerc.h:3037
PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout)
Wait for response from server (blocking).
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.
int charging
charging flag.
Definition: playerc.h:2903
Request/reply: get geometry.
Definition: player_interfaces.h:4112
double max_angle
End angle of scans [rad].
Definition: playerc.h:3030
Position3d device data.
Definition: playerc.h:2776
playerc_putmsg_fn_t putmsg
Standard message callback for this device.
Definition: playerc.h:854
Info about an available (but not necessarily subscribed) device.
Definition: playerc.h:448
struct playerc_blackboard playerc_blackboard_t
BlackBoard proxy.
PLAYERC_EXPORT int playerc_wifi_subscribe(playerc_wifi_t *device, int access)
Subscribe to the wifi device.
PLAYERC_EXPORT playerc_wifi_t * playerc_wifi_create(playerc_client_t *client, int index)
Create a wifi proxy.
int hypoth_count
List of possible poses.
Definition: playerc.h:2237
player_color_t color
current drawing color
Definition: playerc.h:1691
double range_res
Range resolution [m].
Definition: playerc.h:3039
PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access)
Subscribe to the power device.
PLAYERC_EXPORT int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state)
Command to set recording state.
PLAYERC_EXPORT void playerc_health_destroy(playerc_health_t *device)
Destroy a health proxy.
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_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE]
Definition: playerc.h:514
PLAYERC_EXPORT playerc_ranger_t * playerc_ranger_create(playerc_client_t *client, int index)
Create a ranger proxy.
int freshgeom
Freshness flag.
Definition: playerc.h:847
player_audio_seq_t seq_data
last block of seq data
Definition: playerc.h:1092
PLAYERC_EXPORT void playerc_camera_decompress(playerc_camera_t *device)
Decompress the image (modifies the current proxy data).
PLAYERC_EXPORT int playerc_sonar_unsubscribe(playerc_sonar_t *device)
Un-subscribe from the sonar device.
Definition: player_interfaces.h:5102
PLAYERC_EXPORT int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value)
Request an integer property.
A point in the plane.
Definition: player.h:180
PLAYERC_EXPORT playerc_sonar_t * playerc_sonar_create(playerc_client_t *client, int index)
Create a sonar proxy.
player_audio_mixer_channel_list_detail_t channel_details_list
Details of the channels from the mixer.
Definition: playerc.h:1086
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.
char * host
Server address.
Definition: playerc.h:467
Ranger proxy data.
Definition: playerc.h:3019
int8_t * map_cells
Map data (empty = -1, unknown = 0, occupied = +1).
Definition: playerc.h:2228
PLAYERC_EXPORT playerc_aio_t * playerc_aio_create(playerc_client_t *client, int index)
Create a aio proxy.
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_vectormap_subscribe(playerc_vectormap_t *device, int access)
Subscribe to the vectormap device.
PLAYERC_EXPORT int playerc_gripper_store_cmd(playerc_gripper_t *device)
Command the gripper to store.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3562
PLAYERC_EXPORT int playerc_log_unsubscribe(playerc_log_t *device)
Un-subscribe from the log device.
PLAYERC_EXPORT void playerc_laser_destroy(playerc_laser_t *device)
Destroy a laser proxy.
player_pose3d_t device_pose
Device geometry in the robot CS: pose gives the position and orientation, size gives the extent...
Definition: playerc.h:3046
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:989
PLAYERC_EXPORT int playerc_position3d_subscribe(playerc_position3d_t *device, int access)
Subscribe to the position3d device.
uint8_t * guid
The Globally Unique IDentifier (GUID) of the tag.
Definition: playerc.h:3429
PLAYERC_EXPORT playerc_wifi_link_t * playerc_wifi_get_link(playerc_wifi_t *device, int link)
Get link state.
playerc_device_info_t devinfos[PLAYER_MAX_DEVICES]
List of available (but not necessarily subscribed) devices.
Definition: playerc.h:506
PLAYERC_EXPORT void playerc_graphics2d_destroy(playerc_graphics2d_t *device)
Destroy a graphics2d device proxy.
double map_scale
Map scale (m/cell).
Definition: playerc.h:2222
player_vectormap_layer_info_t ** layers_info
Layer info.
Definition: playerc.h:2411
PLAYERC_EXPORT int playerc_ptz_query_status(playerc_ptz_t *device)
Query the pan and tilt status.
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.
double lasttime
Data timestamp from the previous data.
Definition: playerc.h:838
PLAYERC_EXPORT int playerc_device_set_boolprop(playerc_device_t *device, char *property, BOOL value)
Set a boolean property.
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.
int quality
Quality of fix 0 = invalid, 1 = GPS fix, 2 = DGPS fix.
Definition: playerc.h:1591
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_device_set_strprop(playerc_device_t *device, char *property, char *value)
Set a string property.
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_wsn_unsubscribe(playerc_wsn_t *device)
Un-subscribe from the wsn device.
double vminx
Vector-based version of the map (call playerc_map_get_vector() to fill this in).
Definition: playerc.h:2360
double max_range
Maximum range of sensor, in m.
Definition: playerc.h:1989
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_camera_destroy(playerc_camera_t *device)
Destroy a camera proxy.
PLAYERC_EXPORT int playerc_blackboard_set_entry(playerc_blackboard_t *device, player_blackboard_entry_t *entry)
Set an entry value.
uint8_t capacity
The capacity of the gripper's store - if 0, the gripper cannot store.
Definition: playerc.h:1758
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3477
PLAYERC_EXPORT int playerc_speech_say(playerc_speech_t *device, char *)
Set the output for the speech device.
Data: ranges (PLAYER_IR_DATA_RANGES)
Definition: player_interfaces.h:2113
PLAYERC_EXPORT const char * playerc_error_str(void)
Retrieve the last error (as a descriptive string).
double datatime
Data timestamp, i.e., the time at which the data was generated (s).
Definition: playerc.h:835
PLAYERC_EXPORT void playerc_map_destroy(playerc_map_t *device)
Destroy a map proxy.
PLAYERC_EXPORT playerc_blinkenlight_t * playerc_blinkenlight_create(playerc_client_t *client, int index)
Create a blinkenlight proxy.
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 float playerc_aio_get_data(playerc_aio_t *device, uint32_t index)
get the aio data
PLAYERC_EXPORT int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index)
Get the layer data by index.
PTZ device data.
Definition: playerc.h:2937
PLAYERC_EXPORT int playerc_position1d_get_geom(playerc_position1d_t *device)
Get the position1d geometry.
PLAYERC_EXPORT int playerc_speechrecognition_unsubscribe(playerc_speechrecognition_t *device)
Un-subscribe from the speech recognition device.
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.
int bumper_count
Number of points in the scan.
Definition: playerc.h:1352
PLAYERC_EXPORT int playerc_ir_unsubscribe(playerc_ir_t *device)
Un-subscribe from the ir device.
PLAYERC_EXPORT int playerc_imu_unsubscribe(playerc_imu_t *device)
Un-subscribe from the imu device.
void * id
A useful ID for identifying devices; mostly used by other language bindings.
Definition: playerc.h:819
int stall
Stall flag [0, 1].
Definition: playerc.h:2699
PLAYERC_EXPORT void playerc_ranger_destroy(playerc_ranger_t *device)
Destroy a ranger proxy.
PLAYERC_EXPORT int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access)
Subscribe to the blinkenlight device.
uint32_t overflow_count
How many messages were lost on the server due to overflows, incremented by player, cleared by user.
Definition: playerc.h:486
PLAYERC_EXPORT void playerc_wifi_destroy(playerc_wifi_t *device)
Destroy a wifi proxy.
PLAYERC_EXPORT int playerc_ptz_unsubscribe(playerc_ptz_t *device)
Un-subscribe from the ptz device.
Player audio sequence.
Definition: player_interfaces.h:1502
Hypothesis data.
Definition: playerc.h:2205
PLAYERC_EXPORT playerc_vectormap_t * playerc_vectormap_create(playerc_client_t *client, int index)
Create a vectormap proxy.
PLAYERC_EXPORT int playerc_fiducial_unsubscribe(playerc_fiducial_t *device)
Un-subscribe from the fiducial device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1564
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2779
PLAYERC_EXPORT int playerc_actarray_get_geom(playerc_actarray_t *device)
Get the actarray geometry.
PLAYERC_EXPORT int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode)
Change control mode (select velocity or position control)
double scan_res
Angular resolution in radians.
Definition: playerc.h:1983
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.
int path_done
Have we arrived at the goal?
Definition: playerc.h:2517
PLAYERC_EXPORT int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device)
Remove a device proxy.
double angular_res
Scan resolution [rad].
Definition: playerc.h:3032
PLAYERC_EXPORT int playerc_imu_reset_orientation(playerc_imu_t *device, int value)
Reset orientation.
PLAYERC_EXPORT playerc_dio_t * playerc_dio_create(playerc_client_t *client, int index)
Create a dio proxy.
PLAYERC_EXPORT int playerc_simulation_save(playerc_simulation_t *device)
make the simulation save the status/world
PLAYERC_EXPORT int playerc_position2d_set_odom(playerc_position2d_t *device, double ox, double oy, double oa)
Set the odometry offset.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3613
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_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.
double * ranges
Raw range data; range (m).
Definition: playerc.h:1995
double range_res
Range resolution, in m.
Definition: playerc.h:1986
Speech proxy data.
Definition: playerc.h:3348
PLAYERC_EXPORT void playerc_position2d_destroy(playerc_position2d_t *device)
Destroy a position2d device proxy.
Position1d device data.
Definition: playerc.h:2587
uint32_t actuators_count
The number of actuators in the array.
Definition: playerc.h:992
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_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3275
PLAYERC_EXPORT int playerc_position2d_unsubscribe(playerc_position2d_t *device)
Un-subscribe from the position2d device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2590
PLAYERC_EXPORT int playerc_log_get_state(playerc_log_t *device)
Get logging/playback state.
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 int playerc_laser_unsubscribe(playerc_laser_t *device)
Un-subscribe from the laser device.
PLAYERC_EXPORT int playerc_camera_unsubscribe(playerc_camera_t *device)
Un-subscribe from the camera device.
PLAYERC_EXPORT int playerc_opaque_subscribe(playerc_opaque_t *device, int access)
Subscribe to the opaque device.
PLAYERC_EXPORT int playerc_graphics2d_draw_points(playerc_graphics2d_t *device, player_point_2d_t pts[], int count)
Draw some points.
char * data
Definition: playerc.h:518
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 void playerc_device_term(playerc_device_t *device)
Finalize the device.
PLAYERC_EXPORT int playerc_localize_unsubscribe(playerc_localize_t *device)
Un-subscribe from the localize device.
double utm_e
UTM easting and northing (meters).
Definition: playerc.h:1579
PLAYERC_EXPORT int playerc_log_set_read_rewind(playerc_log_t *device)
Rewind playback.
PLAYERC_EXPORT int playerc_health_subscribe(playerc_health_t *device, int access)
Subscribe to the health device.
int scan_id
ID for this scan.
Definition: playerc.h:2009
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.
GPS proxy data.
Definition: playerc.h:1561
PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id, double frequency)
Change data delivery frequency.
uint32_t beams
The position of the object in the gripper.
Definition: playerc.h:1765
PLAYERC_EXPORT void playerc_gripper_destroy(playerc_gripper_t *device)
Destroy a gripper device proxy.
PLAYERC_EXPORT void playerc_client_set_request_timeout(playerc_client_t *client, uint32_t seconds)
Set the timeout for client requests.
Audio device data.
Definition: playerc.h:1080
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition: playerc.h:1752
PLAYERC_EXPORT int playerc_map_unsubscribe(playerc_map_t *device)
Un-subscribe from the map device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1868
PLAYERC_EXPORT int playerc_log_set_read_state(playerc_log_t *device, int state)
Start/stop playback.
PLAYERC_EXPORT int playerc_health_unsubscribe(playerc_health_t *device)
Un-subscribe from the health device.
PLAYERC_EXPORT playerc_health_t * playerc_health_create(playerc_client_t *client, int index)
Create a health proxy.
player_pose3d_t pose
The complete pose of the IMU in 3D coordinates + angles.
Definition: playerc.h:3565
PLAYERC_EXPORT int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode)
Set the velocity mode.
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.
Sonar proxy data.
Definition: playerc.h:3147
Note: the structure describing the HEALTH's data packet is declared in Player.
Definition: playerc.h:1824
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1628
uint32_t element_count
Number of individual elements in the device.
Definition: playerc.h:3025
PLAYERC_EXPORT int playerc_localize_subscribe(playerc_localize_t *device, int access)
Subscribe to the localize device.
PLAYERC_EXPORT playerc_blackboard_t * playerc_blackboard_create(playerc_client_t *client, int index)
Create a blackboard proxy.
PLAYERC_EXPORT int playerc_gripper_subscribe(playerc_gripper_t *device, int access)
Subscribe to the gripper device.
double zoom
The current zoom value (field of view angle).
Definition: playerc.h:2948
PLAYERC_EXPORT int playerc_joystick_unsubscribe(playerc_joystick_t *device)
Un-subscribe from the joystick device.
PLAYERC_EXPORT playerc_power_t * playerc_power_create(playerc_client_t *client, int index)
Create a power device proxy.
uint8_t stored
The number of currently-stored objects.
Definition: playerc.h:1767
uint8_t mode
Definition: playerc.h:493
unsigned int blobs_count
A list of detected blobs.
Definition: playerc.h:1304
playerc_rfidtag_t * tags
The list of RFID tags.
Definition: playerc.h:3442
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3517
PLAYERC_EXPORT int playerc_limb_power(playerc_limb_t *device, uint32_t enable)
Turn the power to the limb on or off.
player_pointcloud3d_element_t playerc_pointcloud3d_element_t
Structure describing a single 3D pointcloud element.
Definition: playerc.h:3471
PLAYERC_EXPORT int playerc_ranger_subscribe(playerc_ranger_t *device, int access)
Subscribe to the ranger 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.
int freshconfig
Freshness flag.
Definition: playerc.h:851
PLAYERC_EXPORT typedef void(* playerc_putmsg_fn_t)(void *device, char *header, char *data)
Typedef for proxy callback function.
Definition: playerc.h:439
uint32_t intensities_count
Number of intensities in a scan.
Definition: playerc.h:3060
PLAYERC_EXPORT int playerc_camera_subscribe(playerc_camera_t *device, int access)
Subscribe to the camera device.
PLAYERC_EXPORT int playerc_limb_stop_cmd(playerc_limb_t *device)
Command the end effector to stop immediatly.
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 int playerc_gps_unsubscribe(playerc_gps_t *device)
Un-subscribe from the gps device.
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 void playerc_joystick_destroy(playerc_joystick_t *device)
Destroy a joystick proxy.
PLAYERC_EXPORT int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device)
Un-subscribe from the graphics2d device.
player_fiducial_geom_t fiducial_geom
Geometry in robot cs.
Definition: playerc.h:1519
PLAYERC_EXPORT playerc_wsn_t * playerc_wsn_create(playerc_client_t *client, int index)
Create a wsn proxy.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1744
Vectormap data.
Definition: player_interfaces.h:5113
Blobfinder device data.
Definition: playerc.h:1295
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc.h:2531
PLAYERC_EXPORT int playerc_pointcloud3d_subscribe(playerc_pointcloud3d_t *device, int access)
Subscribe to the pointcloud3d device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3387
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2344
PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device)
Request the particle set.
PLAYERC_EXPORT int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype)
Request capabilities of device.
PLAYERC_EXPORT playerc_joystick_t * playerc_joystick_create(playerc_client_t *client, int index)
Create a joystick proxy.
PLAYERC_EXPORT int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device)
Un-subscribe from the blinkenlight device.
int status
The current pan and tilt status.
Definition: playerc.h:2951
int fresh
Freshness flag.
Definition: playerc.h:843
player_health_memory_t swap
The swap stats.
Definition: playerc.h:1833
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1242
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 void playerc_audio_destroy(playerc_audio_t *device)
Destroy an audio proxy.
PLAYERC_EXPORT playerc_bumper_t * playerc_bumper_create(playerc_client_t *client, int index)
Create a bumper proxy.
PLAYERC_EXPORT playerc_laser_t * playerc_laser_create(playerc_client_t *client, int index)
Create a laser proxy.
double min_left
Minimum range, in meters, in the left half of the scan (those ranges from the first beam after the mi...
Definition: playerc.h:2022
Graphics2d device data.
Definition: playerc.h:1625
int fiducials_count
List of detected beacons.
Definition: playerc.h:1522
uint32_t ranges_count
Number of ranges in a scan.
Definition: playerc.h:3055
PLAYERC_EXPORT int playerc_pointcloud3d_unsubscribe(playerc_pointcloud3d_t *device)
Un-subscribe from the pointcloud3d device.
player_health_cpu_t cpu_usage
The current cpu usage.
Definition: playerc.h:1829
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1827
player_point_3d_t * points
Scan points (x, y, z).
Definition: playerc.h:3075
uint32_t type
Tag type.
Definition: playerc.h:3425
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1464
playerc_wifi_link_t * links
A list containing info for each link.
Definition: playerc.h:3235
double * scan
Scan data: range (m).
Definition: playerc.h:3163
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_fiducial_subscribe(playerc_fiducial_t *device, int access)
Subscribe to the fiducial device.
PLAYERC_EXPORT int playerc_stereo_subscribe(playerc_stereo_t *device, int access)
Subscribe to the stereo device.
PLAYERC_EXPORT int playerc_log_set_write_state(playerc_log_t *device, int state)
Start/stop logging.
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 void playerc_localize_destroy(playerc_localize_t *device)
Destroy a localize proxy.
PLAYERC_EXPORT playerc_actarray_t * playerc_actarray_create(playerc_client_t *client, int index)
Create an actarray proxy.
PLAYERC_EXPORT int playerc_client_requestdata(playerc_client_t *client)
Request a round of data.
uint32_t guid_count
GUID count.
Definition: playerc.h:3427
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.
int bpp
Image bits-per-pixel (8, 16, 24).
Definition: playerc.h:1404
PLAYERC_EXPORT void playerc_wsn_destroy(playerc_wsn_t *device)
Destroy a wsn proxy.
PLAYERC_EXPORT playerc_client_t * playerc_client_create(playerc_mclient_t *mclient, const char *host, int port)
Create a client object.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1341
PLAYERC_EXPORT void playerc_client_set_retry_limit(playerc_client_t *client, int limit)
Set the connection retry limit.
PLAYERC_EXPORT playerc_rfid_t * playerc_rfid_create(playerc_client_t *client, int index)
Create a rfid proxy.
PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable)
Enable/disable the motors.
Bumper proxy data.
Definition: playerc.h:1338
Log proxy data.
Definition: playerc.h:2281
int sock
Definition: playerc.h:490
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).
double hdop
Horizontal dilution of precision.
Definition: playerc.h:1582
PLAYERC_EXPORT int playerc_blinkenlight_enable(playerc_blinkenlight_t *device, uint32_t enable)
Enable/disable power to the blinkenlight device.
PLAYERC_EXPORT void playerc_client_destroy(playerc_client_t *client)
Destroy a client object.
float q0
Orientation data as quaternions.
Definition: playerc.h:3573
int laser_id
Laser IDentification information.
Definition: playerc.h:2012
Request/reply: get pose.
Definition: player_interfaces.h:2128
PLAYERC_EXPORT void playerc_dio_destroy(playerc_dio_t *device)
Destroy a dio proxy.
PLAYERC_EXPORT int playerc_bumper_subscribe(playerc_bumper_t *device, int access)
Subscribe to the bumper device.
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_client_datamode(playerc_client_t *client, uint8_t mode)
Change the server's data delivery mode.
playerwkbprocessor_t wkbprocessor
WKB processor instance if you want to deal with WKB data.
Definition: playerc.h:2413
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2511
PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device)
Destroy a ptz proxy.
Structure describing a single blob.
Definition: player_interfaces.h:1071
int callback_count
Extra callbacks for this device.
Definition: playerc.h:860
PLAYERC_EXPORT void playerc_position1d_destroy(playerc_position1d_t *device)
Destroy a position1d device proxy.
double datatime
Server time stamp on the last packet.
Definition: playerc.h:525
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2883
Client object data.
Definition: playerc.h:460
int compression
Image compression method.
Definition: playerc.h:1415
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2284
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.
3D Pointcloud element structure An element as stored in a 3D pointcloud, containing a 3D position plu...
Definition: player_interfaces.h:4798
PLAYERC_EXPORT void playerc_position3d_destroy(playerc_position3d_t *device)
Destroy a position3d device proxy.
Position2d device data.
Definition: playerc.h:2681
PLAYERC_EXPORT playerc_position1d_t * playerc_position1d_create(playerc_client_t *client, int index)
Create a position1d device proxy.
Laser proxy data.
Definition: playerc.h:1959
PLAYERC_EXPORT void playerc_ir_destroy(playerc_ir_t *device)
Destroy a ir proxy.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2462
uint8_t * image
Image data (byte aligned, row major order).
Definition: playerc.h:1424
joystick proxy data.
Definition: playerc.h:1914
int map_tile_x
Next map tile to read.
Definition: playerc.h:2225
PLAYERC_EXPORT int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace)
Get the name for a given interface code.
int data_requested
Definition: playerc.h:497
int scan_count
Number of points in the scan.
Definition: playerc.h:3160
double pos_roll
Device orientation (radians).
Definition: playerc.h:2791
PLAYERC_EXPORT int playerc_log_set_filename(playerc_log_t *device, const char *fname)
Change name of log file to write to.
uint16_t tags_count
The number of RFID tags found.
Definition: playerc.h:3439
PLAYERC_EXPORT int playerc_wsn_subscribe(playerc_wsn_t *device, int access)
Subscribe to the wsn device.
PLAYERC_EXPORT int playerc_simulation_pause(playerc_simulation_t *device)
pause / unpause the simulation
Dio proxy data.
Definition: playerc.h:1461
A pose in space.
Definition: player.h:224
PLAYERC_EXPORT void playerc_aio_destroy(playerc_aio_t *device)
Destroy a aio proxy.
PLAYERC_EXPORT int playerc_limb_home_cmd(playerc_limb_t *device)
Command the end effector to move home.
Request/reply: Get geometry.
Definition: player_interfaces.h:1717
uint32_t points_count
Number of scan points.
Definition: playerc.h:3073
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 -.
uint32_t actuators_geom_count
The number of actuators we have geometry for.
Definition: playerc.h:996
uint8_t * data
Data.
Definition: playerc.h:2468
player_pose3d_t * element_poses
Geometry of each individual element in the device (e.g.
Definition: playerc.h:3051
uint32_t node_type
The type of WSN node.
Definition: playerc.h:3616
IMU proxy state data.
Definition: playerc.h:3559
PLAYERC_EXPORT int playerc_client_get_devlist(playerc_client_t *client)
Get the list of available device ids.
PLAYERC_EXPORT playerc_ptz_t * playerc_ptz_create(playerc_client_t *client, int index)
Create a ptz proxy.
PLAYERC_EXPORT int playerc_ranger_unsubscribe(playerc_ranger_t *device)
Un-subscribe from the ranger device.
PLAYERC_EXPORT void playerc_fiducial_destroy(playerc_fiducial_t *device)
Destroy a fiducial proxy.
double percent
Battery charge (percent full).
Definition: playerc.h:2893
uint32_t node_id
The ID of the WSN node.
Definition: playerc.h:3618
double lasttime
Server time stamp on the previous packet.
Definition: playerc.h:527
PLAYERC_EXPORT int playerc_client_read_nonblock(playerc_client_t *client)
Read and process a packet (nonblocking)
int data_received
Definition: playerc.h:501
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 void playerc_actarray_destroy(playerc_actarray_t *device)
Destroy an actarray proxy.
PLAYERC_EXPORT playerc_speechrecognition_t * playerc_speechrecognition_create(playerc_client_t *client, int index)
Create a speech recognition proxy.
player_extent2d_t extent
Boundary area.
Definition: playerc.h:2405
PLAYERC_EXPORT int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device)
Un-subscribe from the blobfinder device.
PLAYERC_EXPORT int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access)
Subscribe to the graphics2d device.
PLAYERC_EXPORT playerc_limb_t * playerc_limb_create(playerc_client_t *client, int index)
Create a limb proxy.
player_bumper_define_t * poses
Pose of each bumper relative to robot (mm, mm, deg, mm, mm).
Definition: playerc.h:1349
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition: playerc.h:1095
A point in 3D space.
Definition: player.h:190
PLAYERC_EXPORT int playerc_gripper_close_cmd(playerc_gripper_t *device)
Command the gripper to close.
int waypoint_count
Number of waypoints in the plan.
Definition: playerc.h:2534
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)
Info on a single detected fiducial.
Definition: player_interfaces.h:1688
void * user_data
Extra user data for this device.
Definition: playerc.h:857
double vdop
Vertical dilution of precision.
Definition: playerc.h:1585
char * cells
Occupancy for each cell (empty = -1, unknown = 0, occupied = +1)
Definition: playerc.h:2356
Definition: playerc.h:391
double pending_time
The timestamp on the last reading processed.
Definition: playerc.h:2234
PLAYERC_EXPORT void playerc_vectormap_destroy(playerc_vectormap_t *device)
Destroy a vectormap proxy.
PLAYERC_EXPORT playerc_pointcloud3d_t * playerc_pointcloud3d_create(playerc_client_t *client, int index)
Create a pointcloud3d proxy.
PLAYERC_EXPORT int playerc_rfid_subscribe(playerc_rfid_t *device, int access)
Subscribe to the rfid device.
PLAYERC_EXPORT int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable)
Turn the power to the array on or off.
PLAYERC_EXPORT int playerc_gripper_open_cmd(playerc_gripper_t *device)
Command the gripper to open.
PLAYERC_EXPORT int playerc_sonar_subscribe(playerc_sonar_t *device, int access)
Subscribe to the sonar device.
PLAYERC_EXPORT int playerc_limb_subscribe(playerc_limb_t *device, int access)
Subscribe to the limb device.
PLAYERC_EXPORT int playerc_planner_enable(playerc_planner_t *device, int state)
Enable / disable the robot's motion.
PLAYERC_EXPORT int playerc_simulation_unsubscribe(playerc_simulation_t *device)
Un-subscribe from the simulation 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...
BlackBoard proxy.
Definition: playerc.h:1178
PLAYERC_EXPORT int playerc_imu_subscribe(playerc_imu_t *device, int access)
Subscribe to the imu device.
PLAYERC_EXPORT int playerc_gripper_retrieve_cmd(playerc_gripper_t *device)
Command the gripper to retrieve.
PLAYERC_EXPORT int playerc_stereo_unsubscribe(playerc_stereo_t *device)
Un-subscribe from the stereo device.
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.
player_point_3d_t base_pos
The position of the base of the actarray.
Definition: playerc.h:1001
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.
double min_range
Minimum range [m].
Definition: playerc.h:3035
char drivername[PLAYER_MAX_DRIVER_STRING_LEN]
The driver name.
Definition: playerc.h:828
double retry_time
How long to sleep, in seconds, to sleep between reconnect attempts.
Definition: playerc.h:483
PLAYERC_EXPORT int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access)
Subscribe to the speech recognition device.
PLAYERC_EXPORT int playerc_position2d_get_geom(playerc_position2d_t *device)
Get the position2d geometry.
Data: Raw audio data.
Definition: player_interfaces.h:1466
int pose_count
Number of pose values.
Definition: playerc.h:3153
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.
struct player_blackboard_entry player_blackboard_entry_t
Vectormap feature data.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1298
PLAYERC_EXPORT playerc_graphics3d_t * playerc_graphics3d_create(playerc_client_t *client, int index)
Create a graphics3d device proxy.
int stall
Stall flag [0, 1].
Definition: playerc.h:2800
PLAYERC_EXPORT int playerc_position3d_unsubscribe(playerc_position3d_t *device)
Un-subscribe from the position3d device.
PLAYERC_EXPORT int playerc_client_connect(playerc_client_t *client)
Connect to the server.
PLAYERC_EXPORT playerc_stereo_t * playerc_stereo_create(playerc_client_t *client, int index)
Create a stereo proxy.
PLAYERC_EXPORT int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value)
Set an integer property.
PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char *group)
Unsubscribe from a group.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2401
void * py_private
Kludge to get around python callback issues.
Definition: playerc.h:1185
int * intensity
Scan reflection intensity values (0-3).
Definition: playerc.h:2006
int subscribed
The subscribe flag is non-zero if the device has been successfully subscribed (read-only).
Definition: playerc.h:832
PLAYERC_EXPORT int playerc_actarray_subscribe(playerc_actarray_t *device, int access)
Subscribe to the actarray device.
PLAYERC_EXPORT int playerc_aio_unsubscribe(playerc_aio_t *device)
Un-subscribe from the aio device.
PLAYERC_EXPORT playerc_camera_t * playerc_camera_create(playerc_client_t *client, int index)
Create a camera proxy.
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_position3d_enable(playerc_position3d_t *device, int enable)
Enable/disable the motors.
void * id
A useful ID for identifying devices; mostly used by other language bindings.
Definition: playerc.h:464
PLAYERC_EXPORT void playerc_imu_destroy(playerc_imu_t *device)
Destroy a imu proxy.
unsigned int width
Image dimensions (pixels).
Definition: playerc.h:1301
PLAYERC_EXPORT int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value)
Turn intensity data on or off.
double wx
Current waypoint location (m, m, radians)
Definition: playerc.h:2526
PLAYERC_EXPORT void playerc_client_set_transport(playerc_client_t *client, unsigned int transport)
Set the transport type.
int format
Image format (e.g., RGB888).
Definition: playerc.h:1407
Wifi device proxy.
Definition: playerc.h:3229
player_devaddr_t addr
Player id of the device.
Definition: playerc.h:451
player_vectormap_layer_data_t ** layers_data
Layer data.
Definition: playerc.h:2409
PLAYERC_EXPORT void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device)
Destroy a speech recognition proxy.
Player mixer channels.
Definition: player_interfaces.h:1572
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_log_subscribe(playerc_log_t *device, int access)
Subscribe to the log device.
PLAYERC_EXPORT void playerc_laser_printout(playerc_laser_t *device, const char *prefix)
Print a human-readable summary of the laser state on stdout.
double * bearings
Scan bearings in the XY plane [radians].
Definition: playerc.h:3070
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition: playerc.h:3483
PLAYERC_EXPORT int playerc_vectormap_unsubscribe(playerc_vectormap_t *device)
Un-subscribe from the vectormap device.
PLAYERC_EXPORT int playerc_sonar_get_geom(playerc_sonar_t *device)
Get the sonar geometry.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1083
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_simulation_subscribe(playerc_simulation_t *device, int access)
Subscribe to the simulation device.
PLAYERC_EXPORT playerc_simulation_t * playerc_simulation_create(playerc_client_t *client, int index)
Create a new simulation proxy.
PLAYERC_EXPORT int playerc_actarray_unsubscribe(playerc_actarray_t *device)
Un-subscribe from the actarray device.
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_wifi_unsubscribe(playerc_wifi_t *device)
Un-subscribe from the wifi device.
PLAYERC_EXPORT int playerc_audio_unsubscribe(playerc_audio_t *device)
Un-subscribe from the audio device.
A line segment, used to construct vector-based maps.
Definition: player.h:287
PLAYERC_EXPORT int playerc_aio_subscribe(playerc_aio_t *device, int access)
Subscribe to the aio device.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:932
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3022
PLAYERC_EXPORT void playerc_client_set_retry_time(playerc_client_t *client, double time)
Set the connection retry sleep time.
PLAYERC_EXPORT int playerc_map_subscribe(playerc_map_t *device, int access)
Subscribe to the map device.
player_wsn_node_data_t data_packet
The WSN node's data packet.
Definition: playerc.h:3622
The geometry of a single bumper.
Definition: player_interfaces.h:1929
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.
int fdiv
Some images (such as disparity maps) use scaled pixel values; for these images, fdiv specifies the sc...
Definition: playerc.h:1412
PLAYERC_EXPORT int playerc_speech_unsubscribe(playerc_speech_t *device)
Un-subscribe from the speech device.
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_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3232
PLAYERC_EXPORT playerc_localize_t * playerc_localize_create(playerc_client_t *client, int index)
Create a localize proxy.
PLAYERC_EXPORT int playerc_position1d_set_cmd_pos(playerc_position1d_t *device, double pos, int state)
Set the target position.
player_devaddr_t addr
Device address.
Definition: playerc.h:825
Limb device data.
Definition: playerc.h:2131
double vel_x
Linear velocity (m/s).
Definition: playerc.h:2794
PLAYERC_EXPORT int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value)
Turn device power on or off.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2216
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2134
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_simulation_reset(playerc_simulation_t *device)
reset the simulation state
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_gripper_stop_cmd(playerc_gripper_t *device)
Command the gripper to stop.
Definition: playerc.h:383
PLAYERC_EXPORT int playerc_fiducial_get_geom(playerc_fiducial_t *device)
Get the fiducial geometry.
PLAYERC_EXPORT int playerc_position1d_set_cmd_vel(playerc_position1d_t *device, double vel, int state)
Set the target speed.
PLAYERC_EXPORT playerc_audio_t * playerc_audio_create(playerc_client_t *client, int index)
Create an audio proxy.
PLAYERC_EXPORT playerc_position2d_t * playerc_position2d_create(playerc_client_t *client, int index)
Create a position2d device proxy.
PLAYERC_EXPORT void playerc_power_destroy(playerc_power_t *device)
Destroy a power device proxy.
PLAYERC_EXPORT int playerc_rfid_unsubscribe(playerc_rfid_t *device)
Un-subscribe from the rfid device.
uint32_t state
current driver state
Definition: playerc.h:1098
PLAYERC_EXPORT int playerc_planner_unsubscribe(playerc_planner_t *device)
Un-subscribe from the planner device.
Player mixer channels.
Definition: player_interfaces.h:1533
enum player_graphics3d_draw_mode player_graphics3d_draw_mode_t
Drawmode: enumeration that defines the drawing mode.
int stall
Stall flag [0, 1].
Definition: playerc.h:2605
Definition: player_interfaces.h:5221
PLAYERC_EXPORT int playerc_audio_subscribe(playerc_audio_t *device, int access)
Subscribe to the audio device.
struct playerc_localize_particle playerc_localize_particle_t
Hypothesis data.
player_actarray_actuator_t * actuators_data
The actuator data, geometry and motor state.
Definition: playerc.h:994
PLAYERC_EXPORT int playerc_gripper_unsubscribe(playerc_gripper_t *device)
Un-subscribe from the gripper device.
PLAYERC_EXPORT void playerc_stereo_destroy(playerc_stereo_t *device)
Destroy a stereo proxy.
int status
Status bitfield of extra data in the following order:
Definition: playerc.h:2618
PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device)
Get the ir geometry.
Hypothesis format.
Definition: player_interfaces.h:2333
PLAYERC_EXPORT int playerc_gps_subscribe(playerc_gps_t *device, int access)
Subscribe to the gps device.
PLAYERC_EXPORT int playerc_client_disconnect_retry(playerc_client_t *client)
Disconnect from the server, with potential retry.
PLAYERC_EXPORT void * playerc_client_read(playerc_client_t *client)
Read data from the server (blocking).
PLAYERC_EXPORT playerc_log_t * playerc_log_create(playerc_client_t *client, int index)
Create a log proxy.
PLAYERC_EXPORT playerc_ir_t * playerc_ir_create(playerc_client_t *client, int index)
Create a ir proxy.
player_orientation_3d_t base_orientation
The orientation of the base of the actarray.
Definition: playerc.h:1003
PLAYERC_EXPORT int playerc_vectormap_get_map_info(playerc_vectormap_t *device)
Get the vectormap metadata, which is stored in the proxy.
Actarray device data.
Definition: playerc.h:986
PLAYERC_EXPORT void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device)
Destroy a blinkenlight proxy.
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_actarray_brakes(playerc_actarray_t *device, uint8_t enable)
Turn the brakes of all actuators in the array that have them on or off.

Last updated 12 September 2005 21:38:45