playerc.h
1 /*
2  * libplayerc : a Player client library
3  * Copyright (C) Andrew Howard and contributors 2002-2007
4  *
5  * This program is free software; you can redistribute it and/or
6  * modify it under the terms of the GNU General Public License
7  * as published by the Free Software Foundation; either version 2
8  * of the License, or (at your option) any later version.
9  *
10  * This program is distributed in the hope that it will be useful,
11  * but WITHOUT ANY WARRANTY; without even the implied warranty of
12  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
13  * GNU General Public License for more details.
14  *
15  * You should have received a copy of the GNU General Public License
16  * along with this program; if not, write to the Free Software
17  * Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA 02110-1301 USA.
18  *
19  */
20 
21 /***************************************************************************
22  * Desc: Player client
23  * Author: Andrew Howard
24  * Date: 24 Aug 2001
25  # CVS: $Id: playerc.h 9140 2014-02-18 02:50:47Z jpgr87 $
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 
380 /***************************************************************************/
386 /***************************************************************************/
387 
392 PLAYERC_EXPORT const char *playerc_error_str(void);
393 
395 /*const char *playerc_lookup_name(int code);*/
396 
398 /*int playerc_lookup_code(const char *name);*/
399 
401 PLAYERC_EXPORT int playerc_add_xdr_ftable(playerxdr_function_t *flist, int replace);
402 
404 /***************************************************************************/
405 
406 
407 /* Forward declare types*/
408 struct _playerc_client_t;
409 struct _playerc_device_t;
410 
411 
412 /* forward declaration to avoid including <sys/poll.h>, which may not be
413  available when people are building clients against this lib*/
414 struct pollfd;
415 
416 
417 /***************************************************************************/
428 /* Items in incoming data queue.*/
429 typedef struct
430 {
431  player_msghdr_t header;
432  void *data;
434 
435 
436 /* Multi-client data*/
437 typedef struct
438 {
439  /* List of clients being managed*/
440  int client_count;
441  struct _playerc_client_t *client[128];
442 
443  /* Poll info*/
444  struct pollfd* pollfd;
445 
446  /* Latest time received from any server*/
447  double time;
448 
450 
451 /* Create a multi-client object*/
452 PLAYERC_EXPORT playerc_mclient_t *playerc_mclient_create(void);
453 
454 /* Destroy a multi-client object*/
455 PLAYERC_EXPORT void playerc_mclient_destroy(playerc_mclient_t *mclient);
456 
457 /* Add a client to the multi-client (private).*/
458 PLAYERC_EXPORT int playerc_mclient_addclient(playerc_mclient_t *mclient, struct _playerc_client_t *client);
459 
460 /* Test to see if there is pending data.
461  Returns -1 on error, 0 or 1 otherwise.*/
462 PLAYERC_EXPORT int playerc_mclient_peek(playerc_mclient_t *mclient, int timeout);
463 
464 /* Read incoming data. The timeout is in ms. Set timeout to a
465  negative value to wait indefinitely.*/
466 PLAYERC_EXPORT int playerc_mclient_read(playerc_mclient_t *mclient, int timeout);
467 
469 /***************************************************************************/
470 
471 
472 /***************************************************************************/
485 PLAYERC_EXPORT typedef void (*playerc_putmsg_fn_t) (void *device, char *header, char *data);
486 
488 PLAYERC_EXPORT typedef void (*playerc_callback_fn_t) (void *data);
489 
490 
494 typedef struct
495 {
498 
501 
503 
504 
506 typedef struct _playerc_client_t
507 {
510  void *id;
511 
513  char *host;
514  int port;
515  int transport;
516  struct sockaddr_in server;
517 
521 
526 
529  double retry_time;
530 
532  uint32_t overflow_count;
533 
534 
536  int sock;
537 
539  uint8_t mode;
540 
544 
548 
549 
553  int devinfo_count;
554 
557  int device_count;
558 
560  playerc_client_item_t qitems[PLAYERC_QUEUE_RING_SIZE];
561  int qfirst, qlen, qsize;
562 
564  char *data;
565  char *read_xdrdata;
566  size_t read_xdrdata_len;
567 
568 
570  double datatime;
572  double lasttime;
573 
574  double request_timeout;
575 
577 
578 
595  const char *host, int port);
596 
602 PLAYERC_EXPORT void playerc_client_destroy(playerc_client_t *client);
603 
609 PLAYERC_EXPORT void playerc_client_set_transport(playerc_client_t* client,
610  unsigned int transport);
611 
620 PLAYERC_EXPORT int playerc_client_connect(playerc_client_t *client);
621 
630 PLAYERC_EXPORT int playerc_client_disconnect(playerc_client_t *client);
631 
638 PLAYERC_EXPORT int playerc_client_disconnect_retry(playerc_client_t *client);
639 
654 PLAYERC_EXPORT int playerc_client_datamode(playerc_client_t *client, uint8_t mode);
655 
667 PLAYERC_EXPORT int playerc_client_requestdata(playerc_client_t* client);
668 
691 PLAYERC_EXPORT int playerc_client_set_replace_rule(playerc_client_t *client, int interf, int index, int type, int subtype, int replace);
692 
693 
696 PLAYERC_EXPORT int playerc_client_adddevice(playerc_client_t *client, struct _playerc_device_t *device);
697 
698 
701 PLAYERC_EXPORT int playerc_client_deldevice(playerc_client_t *client, struct _playerc_device_t *device);
702 
705 PLAYERC_EXPORT int playerc_client_addcallback(playerc_client_t *client, struct _playerc_device_t *device,
706  playerc_callback_fn_t callback, void *data);
707 
710 PLAYERC_EXPORT int playerc_client_delcallback(playerc_client_t *client, struct _playerc_device_t *device,
711  playerc_callback_fn_t callback, void *data);
712 
724 PLAYERC_EXPORT int playerc_client_get_devlist(playerc_client_t *client);
725 
728 PLAYERC_EXPORT int playerc_client_subscribe(playerc_client_t *client, int code, int index,
729  int access, char *drivername, size_t len);
730 
733 PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index);
734 
745 PLAYERC_EXPORT int playerc_client_request(playerc_client_t *client,
746  struct _playerc_device_t *device, uint8_t reqtype,
747  const void *req_data, void **rep_data);
748 
749 
750 /* @brief Wait for response from server (blocking).
751 
752 @param client Pointer to client object.
753 @param device
754 @param index
755 @param sequence
756 
757 @returns Will return data size for ack, -1 for nack and -2 for failure
758 
759 
760 int playerc_client_getresponse(playerc_client_t *client, uint16_t device,
761  uint16_t index, uint16_t sequence, uint8_t * resptype, uint8_t * resp_data, int resp_len);
762 */
763 
764 
776 PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout);
777 
790 PLAYERC_EXPORT int playerc_client_internal_peek(playerc_client_t *client, int timeout);
791 
806 PLAYERC_EXPORT void *playerc_client_read(playerc_client_t *client);
807 
810 PLAYERC_EXPORT int playerc_client_read_nonblock(playerc_client_t *client);
813 PLAYERC_EXPORT int playerc_client_read_nonblock_withproxy(playerc_client_t *client, void ** proxy);
814 
821 PLAYERC_EXPORT void playerc_client_set_request_timeout(playerc_client_t* client, uint32_t seconds);
822 
829 PLAYERC_EXPORT void playerc_client_set_retry_limit(playerc_client_t* client, int limit);
830 
836 PLAYERC_EXPORT void playerc_client_set_retry_time(playerc_client_t* client, double time);
837 
840 PLAYERC_EXPORT int playerc_client_write(playerc_client_t *client,
841  struct _playerc_device_t *device,
842  uint8_t subtype,
843  void *cmd, double* timestamp);
844 
845 
847 /**************************************************************************/
848 
849 
850 /***************************************************************************/
863 typedef struct _playerc_device_t
864 {
868  void *id;
869 
872 
875 
878 
882 
884  double datatime;
885 
887  double lasttime;
888 
892  int fresh;
901 
904 
906  void *user_data;
907 
910  playerc_callback_fn_t callback[4];
911  void *callback_data[4];
912 
914 
915 
917 PLAYERC_EXPORT void playerc_device_init(playerc_device_t *device, playerc_client_t *client,
918  int code, int index, playerc_putmsg_fn_t putmsg);
919 
921 PLAYERC_EXPORT void playerc_device_term(playerc_device_t *device);
922 
924 PLAYERC_EXPORT int playerc_device_subscribe(playerc_device_t *device, int access);
925 
927 PLAYERC_EXPORT int playerc_device_unsubscribe(playerc_device_t *device);
928 
930 PLAYERC_EXPORT int playerc_device_hascapability(playerc_device_t *device, uint32_t type, uint32_t subtype);
931 
933 PLAYERC_EXPORT int playerc_device_get_boolprop(playerc_device_t *device, char *property, BOOL *value);
934 
936 PLAYERC_EXPORT int playerc_device_set_boolprop(playerc_device_t *device, char *property, BOOL value);
937 
939 PLAYERC_EXPORT int playerc_device_get_intprop(playerc_device_t *device, char *property, int32_t *value);
940 
942 PLAYERC_EXPORT int playerc_device_set_intprop(playerc_device_t *device, char *property, int32_t value);
943 
945 PLAYERC_EXPORT int playerc_device_get_dblprop(playerc_device_t *device, char *property, double *value);
946 
948 PLAYERC_EXPORT int playerc_device_set_dblprop(playerc_device_t *device, char *property, double value);
949 
951 PLAYERC_EXPORT int playerc_device_get_strprop(playerc_device_t *device, char *property, char **value);
952 
954 PLAYERC_EXPORT int playerc_device_set_strprop(playerc_device_t *device, char *property, char *value);
955 
956 
958 /**************************************************************************/
959 
960 
961 /***************************************************************************/
966 /***************************************************************************/
967 
968 /**************************************************************************/
978 typedef struct
979 {
982 
983  /* The number of valid analog inputs.*/
984  uint8_t voltages_count;
985 
986  /* A bitfield of the current digital inputs.*/
987  float *voltages;
988 
989 } playerc_aio_t;
990 
991 
993 PLAYERC_EXPORT playerc_aio_t *playerc_aio_create(playerc_client_t *client, int index);
994 
996 PLAYERC_EXPORT void playerc_aio_destroy(playerc_aio_t *device);
997 
999 PLAYERC_EXPORT int playerc_aio_subscribe(playerc_aio_t *device, int access);
1000 
1002 PLAYERC_EXPORT int playerc_aio_unsubscribe(playerc_aio_t *device);
1003 
1005 PLAYERC_EXPORT int playerc_aio_set_output(playerc_aio_t *device, uint8_t id, float volt);
1006 
1008 PLAYERC_EXPORT float playerc_aio_get_data(playerc_aio_t *device, uint32_t index);
1009 
1011 /***************************************************************************/
1012 
1013 
1014 /***************************************************************************/
1025 #define PLAYERC_ACTARRAY_NUM_ACTUATORS PLAYER_ACTARRAY_NUM_ACTUATORS
1026 #define PLAYERC_ACTARRAY_ACTSTATE_IDLE PLAYER_ACTARRAY_ACTSTATE_IDLE
1027 #define PLAYERC_ACTARRAY_ACTSTATE_MOVING PLAYER_ACTARRAY_ACTSTATE_MOVING
1028 #define PLAYERC_ACTARRAY_ACTSTATE_BRAKED PLAYER_ACTARRAY_ACTSTATE_BRAKED
1029 #define PLAYERC_ACTARRAY_ACTSTATE_STALLED PLAYER_ACTARRAY_ACTSTATE_STALLED
1030 #define PLAYERC_ACTARRAY_TYPE_LINEAR PLAYER_ACTARRAY_TYPE_LINEAR
1031 #define PLAYERC_ACTARRAY_TYPE_ROTARY PLAYER_ACTARRAY_TYPE_ROTARY
1032 
1033 
1035 typedef struct
1036 {
1039 
1046  player_actarray_actuatorgeom_t *actuators_geom;
1048  uint8_t motor_state;
1054 
1056 PLAYERC_EXPORT playerc_actarray_t *playerc_actarray_create(playerc_client_t *client, int index);
1057 
1059 PLAYERC_EXPORT void playerc_actarray_destroy(playerc_actarray_t *device);
1060 
1062 PLAYERC_EXPORT int playerc_actarray_subscribe(playerc_actarray_t *device, int access);
1063 
1065 PLAYERC_EXPORT int playerc_actarray_unsubscribe(playerc_actarray_t *device);
1066 
1069 
1072 
1075 PLAYERC_EXPORT int playerc_actarray_get_geom(playerc_actarray_t *device);
1076 
1078 PLAYERC_EXPORT int playerc_actarray_position_cmd(playerc_actarray_t *device, int joint, float position);
1079 
1081 PLAYERC_EXPORT int playerc_actarray_multi_position_cmd(playerc_actarray_t *device, float *positions, int positions_count);
1082 
1084 PLAYERC_EXPORT int playerc_actarray_speed_cmd(playerc_actarray_t *device, int joint, float speed);
1085 
1087 PLAYERC_EXPORT int playerc_actarray_multi_speed_cmd(playerc_actarray_t *device, float *speeds, int speeds_count);
1088 
1090 PLAYERC_EXPORT int playerc_actarray_home_cmd(playerc_actarray_t *device, int joint);
1091 
1093 PLAYERC_EXPORT int playerc_actarray_current_cmd(playerc_actarray_t *device, int joint, float current);
1094 
1096 PLAYERC_EXPORT int playerc_actarray_multi_current_cmd(playerc_actarray_t *device, float *currents, int currents_count);
1097 
1098 
1102 PLAYERC_EXPORT int playerc_actarray_power(playerc_actarray_t *device, uint8_t enable);
1103 
1105 PLAYERC_EXPORT int playerc_actarray_brakes(playerc_actarray_t *device, uint8_t enable);
1106 
1108 PLAYERC_EXPORT int playerc_actarray_speed_config(playerc_actarray_t *device, int joint, float speed);
1109 
1110 /* Set the accelration of a joint (-1 for all joints) for all subsequent movement commands*/
1111 PLAYERC_EXPORT int playerc_actarray_accel_config(playerc_actarray_t *device, int joint, float accel);
1112 
1113 
1115 /**************************************************************************/
1116 
1117 /***************************************************************************/
1129 typedef struct
1130 {
1133 
1136 
1139 
1142 
1145 
1147  uint32_t state;
1148 
1149  int last_index;
1150 
1151 } playerc_audio_t;
1152 
1154 PLAYERC_EXPORT playerc_audio_t *playerc_audio_create(playerc_client_t *client, int index);
1155 
1157 PLAYERC_EXPORT void playerc_audio_destroy(playerc_audio_t *device);
1158 
1160 PLAYERC_EXPORT int playerc_audio_subscribe(playerc_audio_t *device, int access);
1161 
1163 PLAYERC_EXPORT int playerc_audio_unsubscribe(playerc_audio_t *device);
1164 
1166 PLAYERC_EXPORT int playerc_audio_wav_play_cmd(playerc_audio_t *device, uint32_t data_count, uint8_t data[], uint32_t format);
1167 
1169 PLAYERC_EXPORT int playerc_audio_wav_stream_rec_cmd(playerc_audio_t *device, uint8_t state);
1170 
1172 PLAYERC_EXPORT int playerc_audio_sample_play_cmd(playerc_audio_t *device, int index);
1173 
1175 PLAYERC_EXPORT int playerc_audio_seq_play_cmd(playerc_audio_t *device, player_audio_seq_t * tones);
1176 
1179 
1181 PLAYERC_EXPORT int playerc_audio_mixer_channel_cmd(playerc_audio_t *device, uint32_t index, float amplitude, uint8_t active);
1182 
1185 PLAYERC_EXPORT int playerc_audio_wav_rec(playerc_audio_t *device);
1186 
1188 PLAYERC_EXPORT int playerc_audio_sample_load(playerc_audio_t *device, int index, uint32_t data_count, uint8_t data[], uint32_t format);
1189 
1192 PLAYERC_EXPORT int playerc_audio_sample_retrieve(playerc_audio_t *device, int index);
1193 
1195 PLAYERC_EXPORT int playerc_audio_sample_rec(playerc_audio_t *device, int index, uint32_t length);
1196 
1199 PLAYERC_EXPORT int playerc_audio_get_mixer_levels(playerc_audio_t *device);
1200 
1203 PLAYERC_EXPORT int playerc_audio_get_mixer_details(playerc_audio_t *device);
1204 
1206 /**************************************************************************/
1207 
1217 #define PLAYERC_BLACKBOARD_DATA_TYPE_NONE 0
1218 #define PLAYERC_BLACKBOARD_DATA_TYPE_SIMPLE 1
1219 #define PLAYERC_BLACKBOARD_DATA_TYPE_COMPLEX 2
1220 
1221 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_NONE 0
1222 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_STRING 1
1223 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_INT 2
1224 #define PLAYERC_BLACKBOARD_DATA_SUBTYPE_DOUBLE 3
1225 
1227 typedef struct playerc_blackboard
1228 {
1232  void (*on_blackboard_event)(struct playerc_blackboard*, player_blackboard_entry_t);
1234  void *py_private;
1236 
1238 PLAYERC_EXPORT playerc_blackboard_t *playerc_blackboard_create(playerc_client_t *client, int index);
1239 
1241 PLAYERC_EXPORT void playerc_blackboard_destroy(playerc_blackboard_t *device);
1242 
1244 PLAYERC_EXPORT int playerc_blackboard_subscribe(playerc_blackboard_t *device, int access);
1245 
1247 PLAYERC_EXPORT int playerc_blackboard_unsubscribe(playerc_blackboard_t *device);
1248 
1251 PLAYERC_EXPORT int playerc_blackboard_subscribe_to_key(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1252 
1255 PLAYERC_EXPORT int playerc_blackboard_get_entry(playerc_blackboard_t *device, const char* key, const char* group, player_blackboard_entry_t** entry);
1256 
1258 PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_key(playerc_blackboard_t *device, const char* key, const char* group);
1259 
1261 PLAYERC_EXPORT int playerc_blackboard_subscribe_to_group(playerc_blackboard_t *device, const char* group);
1262 
1264 PLAYERC_EXPORT int playerc_blackboard_unsubscribe_from_group(playerc_blackboard_t *device, const char* group);
1265 
1268 
1269 PLAYERC_EXPORT int playerc_blackboard_set_string(playerc_blackboard_t *device, const char* key, const char* group, const char* value);
1270 
1271 PLAYERC_EXPORT int playerc_blackboard_set_int(playerc_blackboard_t *device, const char* key, const char* group, const int value);
1272 
1273 PLAYERC_EXPORT int playerc_blackboard_set_double(playerc_blackboard_t *device, const char* key, const char* group, const double value);
1274 
1277 /**************************************************************************/
1288 typedef struct
1289 {
1292 
1293  uint32_t enabled;
1294  double duty_cycle;
1295  double period;
1296  uint8_t red, green, blue;
1298 
1299 
1301 PLAYERC_EXPORT playerc_blinkenlight_t *playerc_blinkenlight_create(playerc_client_t *client, int index);
1302 
1304 PLAYERC_EXPORT void playerc_blinkenlight_destroy(playerc_blinkenlight_t *device);
1305 
1307 PLAYERC_EXPORT int playerc_blinkenlight_subscribe(playerc_blinkenlight_t *device, int access);
1308 
1310 PLAYERC_EXPORT int playerc_blinkenlight_unsubscribe(playerc_blinkenlight_t *device);
1311 
1313 PLAYERC_EXPORT int playerc_blinkenlight_enable( playerc_blinkenlight_t *device,
1314  uint32_t enable );
1315 
1317 PLAYERC_EXPORT int playerc_blinkenlight_color( playerc_blinkenlight_t *device,
1318  uint32_t id,
1319  uint8_t red,
1320  uint8_t green,
1321  uint8_t blue );
1324 PLAYERC_EXPORT int playerc_blinkenlight_blink( playerc_blinkenlight_t *device,
1325  uint32_t id,
1326  float period,
1327  float duty_cycle );
1330 /***************************************************************************/
1342 
1344 typedef struct
1345 {
1348 
1350  unsigned int width, height;
1351 
1353  unsigned int blobs_count;
1354  playerc_blobfinder_blob_t *blobs;
1355 
1357 
1358 
1360 PLAYERC_EXPORT playerc_blobfinder_t *playerc_blobfinder_create(playerc_client_t *client, int index);
1361 
1363 PLAYERC_EXPORT void playerc_blobfinder_destroy(playerc_blobfinder_t *device);
1364 
1366 PLAYERC_EXPORT int playerc_blobfinder_subscribe(playerc_blobfinder_t *device, int access);
1367 
1369 PLAYERC_EXPORT int playerc_blobfinder_unsubscribe(playerc_blobfinder_t *device);
1370 
1371 
1373 /**************************************************************************/
1374 
1375 
1376 /**************************************************************************/
1387 typedef struct
1388 {
1391 
1394 
1399 
1402 
1404  uint8_t *bumpers;
1405 
1407 
1408 
1410 PLAYERC_EXPORT playerc_bumper_t *playerc_bumper_create(playerc_client_t *client, int index);
1411 
1413 PLAYERC_EXPORT void playerc_bumper_destroy(playerc_bumper_t *device);
1414 
1416 PLAYERC_EXPORT int playerc_bumper_subscribe(playerc_bumper_t *device, int access);
1417 
1419 PLAYERC_EXPORT int playerc_bumper_unsubscribe(playerc_bumper_t *device);
1420 
1427 PLAYERC_EXPORT int playerc_bumper_get_geom(playerc_bumper_t *device);
1428 
1429 
1431 /***************************************************************************/
1432 
1433 
1434 /***************************************************************************/
1444 typedef struct
1445 {
1448 
1450  int width, height;
1451 
1453  int bpp;
1454 
1456  int format;
1457 
1461  int fdiv;
1462 
1465 
1468 
1473  uint8_t *image;
1474 
1476  char norm[16];
1477  int source;
1478 
1480 
1481 
1483 PLAYERC_EXPORT playerc_camera_t *playerc_camera_create(playerc_client_t *client, int index);
1484 
1486 PLAYERC_EXPORT void playerc_camera_destroy(playerc_camera_t *device);
1487 
1489 PLAYERC_EXPORT int playerc_camera_subscribe(playerc_camera_t *device, int access);
1490 
1492 PLAYERC_EXPORT int playerc_camera_unsubscribe(playerc_camera_t *device);
1493 
1495 PLAYERC_EXPORT void playerc_camera_decompress(playerc_camera_t *device);
1496 
1498 PLAYERC_EXPORT void playerc_camera_save(playerc_camera_t *device, const char *filename);
1499 
1501 PLAYERC_EXPORT int playerc_camera_set_source(playerc_camera_t *device, int source, const char *norm);
1502 
1504 PLAYERC_EXPORT int playerc_camera_get_source(playerc_camera_t *device);
1505 
1507 PLAYERC_EXPORT int playerc_camera_get_image(playerc_camera_t *device);
1508 
1510 PLAYERC_EXPORT void playerc_camera_copy_image(playerc_camera_t * device, void * dst, size_t dst_size);
1511 
1513 PLAYERC_EXPORT unsigned playerc_camera_get_pixel_component(playerc_camera_t * device, unsigned int x, unsigned int y, int component);
1514 
1516 /**************************************************************************/
1517 
1518 /**************************************************************************/
1531 typedef struct
1532 {
1535 
1538 
1544  uint8_t origin;
1546  uint16_t id;
1548  uint16_t parent_id;
1549 
1553  uint16_t RSSIsender;
1554  uint16_t RSSIvalue;
1555  uint16_t RSSIstamp;
1556  uint32_t RSSInodeTimeHigh;
1557  uint32_t RSSInodeTimeLow;
1558 
1560  float x;
1561  float y;
1562  float z;
1563 
1564  uint8_t status;
1565 
1574 
1578  uint8_t *user_data;
1579 
1581  uint8_t command;
1583  uint8_t request;
1587  uint8_t *parameters;
1588 
1590 
1591 
1593 PLAYERC_EXPORT playerc_coopobject_t *playerc_coopobject_create(playerc_client_t *client, int index);
1594 
1596 PLAYERC_EXPORT void playerc_coopobject_destroy(playerc_coopobject_t *device);
1597 
1599 PLAYERC_EXPORT int playerc_coopobject_subscribe(playerc_coopobject_t *device, int access);
1600 
1602 PLAYERC_EXPORT int playerc_coopobject_unsubscribe(playerc_coopobject_t *device);
1603 
1605 PLAYERC_EXPORT int playerc_coopobject_send_position(playerc_coopobject_t *device, uint16_t node_id, uint16_t source_id, player_pose2d_t pos, uint8_t status);
1606 
1608 PLAYERC_EXPORT int playerc_coopobject_send_data(playerc_coopobject_t *device, int node_id, int source_id, int data_type, int data_size, unsigned char *extradata);
1609 
1611 PLAYERC_EXPORT int playerc_coopobject_send_cmd(playerc_coopobject_t *device, int node_id, int source_id, int cmd, int parameters_size, unsigned char *parameters);
1612 
1614 PLAYERC_EXPORT int playerc_coopobject_send_req(playerc_coopobject_t *device, int node_id, int source_id, int req, int parameters_size, unsigned char *parameters);
1615 
1616 // /** Put the node in sleep mode (0) or wake it up (1). */
1617 //PLAYERC_EXPORT int playerc_coopobject_power(playerc_coopobject_t *device, int node_id, int group_id, int value);
1618 
1619 // /** Change the data type to RAW or converted engineering units. */
1620 //PLAYERC_EXPORT int playerc_coopobject_datatype(playerc_coopobject_t *device, int value);
1621 
1622 // /** Change data delivery frequency. */
1623 //PLAYERC_EXPORT int playerc_coopobject_datafreq(playerc_coopobject_t *device, int node_id, int group_id, double frequency);
1624 
1626 /***************************************************************************/
1627 
1628 /**************************************************************************/
1638 typedef struct
1639 {
1642 
1643  /*/ The number of valid digital inputs.*/
1644  uint8_t count;
1645 
1646  /*/ A bitfield of the current digital inputs.*/
1647  uint32_t digin;
1648 
1649 } playerc_dio_t;
1650 
1651 
1653 PLAYERC_EXPORT playerc_dio_t *playerc_dio_create(playerc_client_t *client, int index);
1654 
1656 PLAYERC_EXPORT void playerc_dio_destroy(playerc_dio_t *device);
1657 
1659 PLAYERC_EXPORT int playerc_dio_subscribe(playerc_dio_t *device, int access);
1660 
1662 PLAYERC_EXPORT int playerc_dio_unsubscribe(playerc_dio_t *device);
1663 
1665 PLAYERC_EXPORT int playerc_dio_set_output(playerc_dio_t *device, uint8_t output_count, uint32_t digout);
1666 
1667 
1669 /***************************************************************************/
1670 
1671 
1672 /***************************************************************************/
1687 typedef struct
1688 {
1691 
1697 
1700  player_fiducial_item_t *fiducials;
1701 
1703 
1704 
1706 PLAYERC_EXPORT playerc_fiducial_t *playerc_fiducial_create(playerc_client_t *client, int index);
1707 
1709 PLAYERC_EXPORT void playerc_fiducial_destroy(playerc_fiducial_t *device);
1710 
1712 PLAYERC_EXPORT int playerc_fiducial_subscribe(playerc_fiducial_t *device, int access);
1713 
1715 PLAYERC_EXPORT int playerc_fiducial_unsubscribe(playerc_fiducial_t *device);
1716 
1723 PLAYERC_EXPORT int playerc_fiducial_get_geom(playerc_fiducial_t *device);
1724 
1725 
1727 /**************************************************************************/
1728 
1729 /***************************************************************************/
1740 typedef struct
1741 {
1744 
1746  double utc_time;
1747 
1751  double lat, lon;
1752 
1755  double alt;
1756 
1758  double speed;
1759 
1762  double course;
1763 
1765  double utm_e, utm_n;
1766 
1768  double hdop;
1769 
1771  double vdop;
1772 
1774  double err_horz, err_vert;
1775 
1777  int quality;
1778 
1781 
1782 } playerc_gps_t;
1783 
1784 
1786 PLAYERC_EXPORT playerc_gps_t *playerc_gps_create(playerc_client_t *client, int index);
1787 
1789 PLAYERC_EXPORT void playerc_gps_destroy(playerc_gps_t *device);
1790 
1792 PLAYERC_EXPORT int playerc_gps_subscribe(playerc_gps_t *device, int access);
1793 
1795 PLAYERC_EXPORT int playerc_gps_unsubscribe(playerc_gps_t *device);
1796 
1797 
1799 /**************************************************************************/
1800 
1801 /***************************************************************************/
1811 typedef struct
1812 {
1815 
1818 
1820 
1821 
1823 PLAYERC_EXPORT playerc_graphics2d_t *playerc_graphics2d_create(playerc_client_t *client, int index);
1824 
1826 PLAYERC_EXPORT void playerc_graphics2d_destroy(playerc_graphics2d_t *device);
1827 
1829 PLAYERC_EXPORT int playerc_graphics2d_subscribe(playerc_graphics2d_t *device, int access);
1830 
1832 PLAYERC_EXPORT int playerc_graphics2d_unsubscribe(playerc_graphics2d_t *device);
1833 
1835 PLAYERC_EXPORT int playerc_graphics2d_setcolor(playerc_graphics2d_t *device,
1836  player_color_t col );
1837 
1839 PLAYERC_EXPORT int playerc_graphics2d_draw_points(playerc_graphics2d_t *device,
1840  player_point_2d_t pts[],
1841  int count );
1842 
1844 PLAYERC_EXPORT int playerc_graphics2d_draw_polyline(playerc_graphics2d_t *device,
1845  player_point_2d_t pts[],
1846  int count );
1847 
1849 PLAYERC_EXPORT int playerc_graphics2d_draw_multiline(playerc_graphics2d_t *device,
1850  player_point_2d_t pts[],
1851  int count );
1852 
1853 
1854 
1856 PLAYERC_EXPORT int playerc_graphics2d_draw_polygon(playerc_graphics2d_t *device,
1857  player_point_2d_t pts[],
1858  int count,
1859  int filled,
1860  player_color_t fill_color );
1861 
1863 PLAYERC_EXPORT int playerc_graphics2d_clear(playerc_graphics2d_t *device );
1864 
1865 
1868 /***************************************************************************/
1878 typedef struct
1879 {
1882 
1885 
1887 
1888 
1890 PLAYERC_EXPORT playerc_graphics3d_t *playerc_graphics3d_create(playerc_client_t *client, int index);
1891 
1893 PLAYERC_EXPORT void playerc_graphics3d_destroy(playerc_graphics3d_t *device);
1894 
1896 PLAYERC_EXPORT int playerc_graphics3d_subscribe(playerc_graphics3d_t *device, int access);
1897 
1899 PLAYERC_EXPORT int playerc_graphics3d_unsubscribe(playerc_graphics3d_t *device);
1900 
1902 PLAYERC_EXPORT int playerc_graphics3d_setcolor(playerc_graphics3d_t *device,
1903  player_color_t col );
1904 
1906 PLAYERC_EXPORT int playerc_graphics3d_draw(playerc_graphics3d_t *device,
1908  player_point_3d_t pts[],
1909  int count );
1910 
1912 PLAYERC_EXPORT int playerc_graphics3d_clear(playerc_graphics3d_t *device );
1913 
1915 PLAYERC_EXPORT int playerc_graphics3d_translate(playerc_graphics3d_t *device,
1916  double x, double y, double z );
1917 
1918 
1920 PLAYERC_EXPORT int playerc_graphics3d_rotate( playerc_graphics3d_t *device,
1921  double a, double x, double y, double z );
1924 /***************************************************************************/
1934 typedef struct
1935 {
1938 
1946  player_bbox3d_t outer_size;
1947  player_bbox3d_t inner_size;
1949  uint8_t num_beams;
1951  uint8_t capacity;
1952 
1956  uint8_t state;
1958  uint32_t beams;
1960  uint8_t stored;
1962 
1964 PLAYERC_EXPORT playerc_gripper_t *playerc_gripper_create(playerc_client_t *client, int index);
1965 
1967 PLAYERC_EXPORT void playerc_gripper_destroy(playerc_gripper_t *device);
1968 
1970 PLAYERC_EXPORT int playerc_gripper_subscribe(playerc_gripper_t *device, int access);
1971 
1973 PLAYERC_EXPORT int playerc_gripper_unsubscribe(playerc_gripper_t *device);
1974 
1976 PLAYERC_EXPORT int playerc_gripper_open_cmd(playerc_gripper_t *device);
1977 
1979 PLAYERC_EXPORT int playerc_gripper_close_cmd(playerc_gripper_t *device);
1980 
1982 PLAYERC_EXPORT int playerc_gripper_stop_cmd(playerc_gripper_t *device);
1983 
1985 PLAYERC_EXPORT int playerc_gripper_store_cmd(playerc_gripper_t *device);
1986 
1988 PLAYERC_EXPORT int playerc_gripper_retrieve_cmd(playerc_gripper_t *device);
1989 
1992 PLAYERC_EXPORT void playerc_gripper_printout(playerc_gripper_t *device, const char* prefix);
1993 
1998 PLAYERC_EXPORT int playerc_gripper_get_geom(playerc_gripper_t *device);
1999 
2001 /**************************************************************************/
2002 
2003 /***************************************************************************/
2017 typedef struct
2018 {
2028 
2029 
2031 PLAYERC_EXPORT playerc_health_t *playerc_health_create(playerc_client_t *client, int index);
2032 
2034 PLAYERC_EXPORT void playerc_health_destroy(playerc_health_t *device);
2035 
2037 PLAYERC_EXPORT int playerc_health_subscribe(playerc_health_t *device, int access);
2038 
2040 PLAYERC_EXPORT int playerc_health_unsubscribe(playerc_health_t *device);
2041 
2042 
2044 /***************************************************************************/
2045 
2046 
2047 /***************************************************************************/
2058 typedef struct
2059 {
2062 
2063  /* data*/
2065 
2066  /* config*/
2067  player_ir_pose_t poses;
2068 
2069 } playerc_ir_t;
2070 
2071 
2073 PLAYERC_EXPORT playerc_ir_t *playerc_ir_create(playerc_client_t *client, int index);
2074 
2076 PLAYERC_EXPORT void playerc_ir_destroy(playerc_ir_t *device);
2077 
2079 PLAYERC_EXPORT int playerc_ir_subscribe(playerc_ir_t *device, int access);
2080 
2082 PLAYERC_EXPORT int playerc_ir_unsubscribe(playerc_ir_t *device);
2083 
2090 PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device);
2091 
2092 
2094 /***************************************************************************/
2095 
2096 
2097 /***************************************************************************/
2107 typedef struct
2108 {
2111  int32_t axes_count;
2112  int32_t pos[8];
2113  uint32_t buttons;
2114  int * axes_max;
2115  int * axes_min;
2116  double * scale_pos;
2117 
2118 
2120 
2121 
2123 PLAYERC_EXPORT playerc_joystick_t *playerc_joystick_create(playerc_client_t *client, int index);
2124 
2126 PLAYERC_EXPORT void playerc_joystick_destroy(playerc_joystick_t *device);
2127 
2129 PLAYERC_EXPORT int playerc_joystick_subscribe(playerc_joystick_t *device, int access);
2130 
2132 PLAYERC_EXPORT int playerc_joystick_unsubscribe(playerc_joystick_t *device);
2133 
2135 /**************************************************************************/
2136 
2137 
2138 /***************************************************************************/
2152 typedef struct
2153 {
2156 
2160  double pose[3];
2161  double size[2];
2162 
2164  double robot_pose[3];
2165 
2168 
2171 
2173  double scan_start;
2174 
2176  double scan_res;
2177 
2179  double range_res;
2180 
2182  double max_range;
2183 
2186 
2188  double *ranges;
2189 
2191  double (*scan)[2];
2192 
2195 
2200 
2202  int scan_id;
2203 
2206 
2210  double min_right;
2211 
2215  double min_left;
2216 } playerc_laser_t;
2217 
2218 
2220 PLAYERC_EXPORT playerc_laser_t *playerc_laser_create(playerc_client_t *client, int index);
2221 
2223 PLAYERC_EXPORT void playerc_laser_destroy(playerc_laser_t *device);
2224 
2226 PLAYERC_EXPORT int playerc_laser_subscribe(playerc_laser_t *device, int access);
2227 
2229 PLAYERC_EXPORT int playerc_laser_unsubscribe(playerc_laser_t *device);
2230 
2253 PLAYERC_EXPORT int playerc_laser_set_config(playerc_laser_t *device,
2254  double min_angle, double max_angle,
2255  double resolution,
2256  double range_res,
2257  unsigned char intensity,
2258  double scanning_frequency);
2259 
2282 PLAYERC_EXPORT int playerc_laser_get_config(playerc_laser_t *device,
2283  double *min_angle,
2284  double *max_angle,
2285  double *resolution,
2286  double *range_res,
2287  unsigned char *intensity,
2288  double *scanning_frequency);
2289 
2296 PLAYERC_EXPORT int playerc_laser_get_geom(playerc_laser_t *device);
2297 
2302 PLAYERC_EXPORT int playerc_laser_get_id (playerc_laser_t *device);
2303 
2306 PLAYERC_EXPORT void playerc_laser_printout( playerc_laser_t * device,
2307  const char* prefix );
2308 
2310 /**************************************************************************/
2311 
2312 
2324 typedef struct
2325 {
2328 
2331 } playerc_limb_t;
2332 
2334 PLAYERC_EXPORT playerc_limb_t *playerc_limb_create(playerc_client_t *client, int index);
2335 
2337 PLAYERC_EXPORT void playerc_limb_destroy(playerc_limb_t *device);
2338 
2340 PLAYERC_EXPORT int playerc_limb_subscribe(playerc_limb_t *device, int access);
2341 
2343 PLAYERC_EXPORT int playerc_limb_unsubscribe(playerc_limb_t *device);
2344 
2347 PLAYERC_EXPORT int playerc_limb_get_geom(playerc_limb_t *device);
2348 
2350 PLAYERC_EXPORT int playerc_limb_home_cmd(playerc_limb_t *device);
2351 
2353 PLAYERC_EXPORT int playerc_limb_stop_cmd(playerc_limb_t *device);
2354 
2356 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);
2357 
2360 PLAYERC_EXPORT int playerc_limb_setposition_cmd(playerc_limb_t *device, float pX, float pY, float pZ);
2361 
2364 PLAYERC_EXPORT int playerc_limb_vecmove_cmd(playerc_limb_t *device, float x, float y, float z, float length);
2365 
2369 PLAYERC_EXPORT int playerc_limb_power(playerc_limb_t *device, uint32_t enable);
2370 
2372 PLAYERC_EXPORT int playerc_limb_brakes(playerc_limb_t *device, uint32_t enable);
2373 
2375 PLAYERC_EXPORT int playerc_limb_speed_config(playerc_limb_t *device, float speed);
2376 
2378 /**************************************************************************/
2379 
2380 
2381 /***************************************************************************/
2399 {
2400  double pose[3];
2401  double weight;
2403 
2404 
2406 typedef struct
2407 {
2410 
2412  int map_size_x, map_size_y;
2413 
2415  double map_scale;
2416 
2418  int map_tile_x, map_tile_y;
2419 
2421  int8_t *map_cells;
2422 
2425 
2428 
2431  player_localize_hypoth_t *hypoths;
2432 
2433  double mean[3];
2434  double variance;
2435  int num_particles;
2436  playerc_localize_particle_t *particles;
2437 
2439 
2440 
2442 PLAYERC_EXPORT playerc_localize_t *playerc_localize_create(playerc_client_t *client, int index);
2443 
2445 PLAYERC_EXPORT void playerc_localize_destroy(playerc_localize_t *device);
2446 
2448 PLAYERC_EXPORT int playerc_localize_subscribe(playerc_localize_t *device, int access);
2449 
2451 PLAYERC_EXPORT int playerc_localize_unsubscribe(playerc_localize_t *device);
2452 
2454 PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[6]);
2455 
2458 PLAYERC_EXPORT int playerc_localize_get_particles(playerc_localize_t *device);
2459 
2461 /**************************************************************************/
2462 
2463 
2464 /***************************************************************************/
2474 typedef struct
2475 {
2478 
2481  int type;
2482 
2485  int state;
2486 } playerc_log_t;
2487 
2488 
2490 PLAYERC_EXPORT playerc_log_t *playerc_log_create(playerc_client_t *client, int index);
2491 
2493 PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device);
2494 
2496 PLAYERC_EXPORT int playerc_log_subscribe(playerc_log_t *device, int access);
2497 
2499 PLAYERC_EXPORT int playerc_log_unsubscribe(playerc_log_t *device);
2500 
2502 PLAYERC_EXPORT int playerc_log_set_write_state(playerc_log_t* device, int state);
2503 
2505 PLAYERC_EXPORT int playerc_log_set_read_state(playerc_log_t* device, int state);
2506 
2508 PLAYERC_EXPORT int playerc_log_set_read_rewind(playerc_log_t* device);
2509 
2515 PLAYERC_EXPORT int playerc_log_get_state(playerc_log_t* device);
2516 
2518 PLAYERC_EXPORT int playerc_log_set_filename(playerc_log_t* device, const char* fname);
2519 
2520 
2524 /***************************************************************************/
2534 typedef struct
2535 {
2538 
2540  double resolution;
2541 
2543  int width, height;
2544 
2546  double origin[2];
2547 
2549  int8_t data_range;
2550 
2552  char* cells;
2553 
2556  double vminx, vminy, vmaxx, vmaxy;
2557  int num_segments;
2558  player_segment_t* segments;
2559 } playerc_map_t;
2560 
2563 #define PLAYERC_MAP_INDEX(dev, i, j) ((dev->width) * (j) + (i))
2564 
2566 PLAYERC_EXPORT playerc_map_t *playerc_map_create(playerc_client_t *client, int index);
2567 
2569 PLAYERC_EXPORT void playerc_map_destroy(playerc_map_t *device);
2570 
2572 PLAYERC_EXPORT int playerc_map_subscribe(playerc_map_t *device, int access);
2573 
2575 PLAYERC_EXPORT int playerc_map_unsubscribe(playerc_map_t *device);
2576 
2578 PLAYERC_EXPORT int playerc_map_get_map(playerc_map_t* device);
2579 
2581 PLAYERC_EXPORT int playerc_map_get_vector(playerc_map_t* device);
2582 
2584 /**************************************************************************/
2585 
2594 typedef struct
2595 {
2599  uint32_t srid;
2603  uint32_t layers_count;
2609  playerwkbprocessor_t wkbprocessor;
2610 
2612 
2614 PLAYERC_EXPORT playerc_vectormap_t *playerc_vectormap_create(playerc_client_t *client, int index);
2615 
2617 PLAYERC_EXPORT void playerc_vectormap_destroy(playerc_vectormap_t *device);
2618 
2620 PLAYERC_EXPORT int playerc_vectormap_subscribe(playerc_vectormap_t *device, int access);
2621 
2623 PLAYERC_EXPORT int playerc_vectormap_unsubscribe(playerc_vectormap_t *device);
2624 
2626 PLAYERC_EXPORT int playerc_vectormap_get_map_info(playerc_vectormap_t* device);
2627 
2629 PLAYERC_EXPORT int playerc_vectormap_get_layer_data(playerc_vectormap_t *device, unsigned layer_index);
2630 
2633 
2635 PLAYERC_EXPORT void playerc_vectormap_cleanup(playerc_vectormap_t *device);
2636 
2639 PLAYERC_EXPORT uint8_t * playerc_vectormap_get_feature_data(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2640 PLAYERC_EXPORT size_t playerc_vectormap_get_feature_data_count(playerc_vectormap_t *device, unsigned layer_index, unsigned feature_index);
2641 
2644 /***************************************************************************/
2655 typedef struct
2656 {
2659 
2662 
2664  uint8_t *data;
2666 
2668 PLAYERC_EXPORT playerc_opaque_t *playerc_opaque_create(playerc_client_t *client, int index);
2669 
2671 PLAYERC_EXPORT void playerc_opaque_destroy(playerc_opaque_t *device);
2672 
2674 PLAYERC_EXPORT int playerc_opaque_subscribe(playerc_opaque_t *device, int access);
2675 
2677 PLAYERC_EXPORT int playerc_opaque_unsubscribe(playerc_opaque_t *device);
2678 
2680 PLAYERC_EXPORT int playerc_opaque_cmd(playerc_opaque_t *device, player_opaque_data_t *data);
2681 
2688 PLAYERC_EXPORT int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply);
2689 
2691 /**************************************************************************/
2692 
2693 
2694 /***************************************************************************/
2704 typedef struct
2705 {
2708 
2711 
2714 
2716  double px, py, pa;
2717 
2719  double gx, gy, ga;
2720 
2722  double wx, wy, wa;
2723 
2728 
2731 
2734  double (*waypoints)[3];
2735 
2739 
2741 
2743 PLAYERC_EXPORT playerc_planner_t *playerc_planner_create(playerc_client_t *client, int index);
2744 
2746 PLAYERC_EXPORT void playerc_planner_destroy(playerc_planner_t *device);
2747 
2749 PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access);
2750 
2752 PLAYERC_EXPORT int playerc_planner_unsubscribe(playerc_planner_t *device);
2753 
2755 PLAYERC_EXPORT int playerc_planner_set_cmd_pose(playerc_planner_t *device,
2756  double gx, double gy, double ga);
2757 
2759 PLAYERC_EXPORT int playerc_planner_set_cmd_start(playerc_planner_t *device,
2760  double sx, double sy, double sa);
2761 
2768 PLAYERC_EXPORT int playerc_planner_get_waypoints(playerc_planner_t *device);
2769 
2775 PLAYERC_EXPORT int playerc_planner_enable(playerc_planner_t *device, int state);
2776 
2778 /**************************************************************************/
2779 
2780 /***************************************************************************/
2791 typedef struct
2792 {
2795 
2799  double pose[3];
2800  double size[2];
2801 
2803  double pos;
2804 
2806  double vel;
2807 
2809  int stall;
2810 
2822  int status;
2823 
2825 
2828  int index);
2829 
2831 PLAYERC_EXPORT void playerc_position1d_destroy(playerc_position1d_t *device);
2832 
2834 PLAYERC_EXPORT int playerc_position1d_subscribe(playerc_position1d_t *device, int access);
2835 
2837 PLAYERC_EXPORT int playerc_position1d_unsubscribe(playerc_position1d_t *device);
2838 
2840 PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable);
2841 
2844 PLAYERC_EXPORT int playerc_position1d_get_geom(playerc_position1d_t *device);
2845 
2847 PLAYERC_EXPORT int playerc_position1d_set_cmd_vel(playerc_position1d_t *device,
2848  double vel, int state);
2849 
2853 PLAYERC_EXPORT int playerc_position1d_set_cmd_pos(playerc_position1d_t *device,
2854  double pos, int state);
2855 
2861  double pos, double vel, int state);
2862 
2864 PLAYERC_EXPORT int playerc_position1d_set_odom(playerc_position1d_t *device,
2865  double odom);
2866 
2868 /**************************************************************************/
2869 
2870 
2871 /***************************************************************************/
2885 typedef struct
2886 {
2889 
2893  double pose[3];
2894  double size[2];
2895 
2897  double px, py, pa;
2898 
2900  double vx, vy, va;
2901 
2903  int stall;
2904 
2906 
2909  int index);
2910 
2912 PLAYERC_EXPORT void playerc_position2d_destroy(playerc_position2d_t *device);
2913 
2915 PLAYERC_EXPORT int playerc_position2d_subscribe(playerc_position2d_t *device, int access);
2916 
2918 PLAYERC_EXPORT int playerc_position2d_unsubscribe(playerc_position2d_t *device);
2919 
2921 PLAYERC_EXPORT int playerc_position2d_enable(playerc_position2d_t *device, int enable);
2922 
2925 PLAYERC_EXPORT int playerc_position2d_get_geom(playerc_position2d_t *device);
2926 
2931 PLAYERC_EXPORT int playerc_position2d_set_cmd_vel(playerc_position2d_t *device,
2932  double vx, double vy, double va, int state);
2933 
2936  player_pose2d_t pos,
2937  player_pose2d_t vel,
2938  int state);
2939 
2945  double vx, double vy, double pa, int state);
2946 
2947 
2948 
2951 PLAYERC_EXPORT int playerc_position2d_set_cmd_pose(playerc_position2d_t *device,
2952  double gx, double gy, double ga, int state);
2953 
2955 PLAYERC_EXPORT int playerc_position2d_set_cmd_car(playerc_position2d_t *device,
2956  double vx, double a);
2957 
2959 PLAYERC_EXPORT int playerc_position2d_set_odom(playerc_position2d_t *device,
2960  double ox, double oy, double oa);
2961 
2963 /**************************************************************************/
2964 
2965 /***************************************************************************/
2980 typedef struct
2981 {
2984 
2988  double pose[3];
2989  double size[2];
2990 
2992  double pos_x, pos_y, pos_z;
2993 
2995  double pos_roll, pos_pitch, pos_yaw;
2996 
2998  double vel_x, vel_y, vel_z;
2999 
3001  double vel_roll, vel_pitch, vel_yaw;
3002 
3004  int stall;
3005 
3007 
3008 
3011  int index);
3012 
3014 PLAYERC_EXPORT void playerc_position3d_destroy(playerc_position3d_t *device);
3015 
3017 PLAYERC_EXPORT int playerc_position3d_subscribe(playerc_position3d_t *device, int access);
3018 
3020 PLAYERC_EXPORT int playerc_position3d_unsubscribe(playerc_position3d_t *device);
3021 
3023 PLAYERC_EXPORT int playerc_position3d_enable(playerc_position3d_t *device, int enable);
3024 
3027 PLAYERC_EXPORT int playerc_position3d_get_geom(playerc_position3d_t *device);
3028 
3033 PLAYERC_EXPORT int playerc_position3d_set_velocity(playerc_position3d_t *device,
3034  double vx, double vy, double vz,
3035  double vr, double vp, double vt,
3036  int state);
3037 
3039 PLAYERC_EXPORT int playerc_position3d_set_speed(playerc_position3d_t *device,
3040  double vx, double vy, double vz, int state);
3041 
3044 PLAYERC_EXPORT int playerc_position3d_set_pose(playerc_position3d_t *device,
3045  double gx, double gy, double gz,
3046  double gr, double gp, double gt);
3047 
3048 
3051  player_pose3d_t pos,
3052  player_pose3d_t vel);
3053 
3055 PLAYERC_EXPORT int playerc_position3d_set_cmd_pose(playerc_position3d_t *device,
3056  double gx, double gy, double gz);
3057 
3059 PLAYERC_EXPORT int playerc_position3d_set_vel_mode(playerc_position3d_t *device, int mode);
3060 
3062 PLAYERC_EXPORT int playerc_position3d_set_odom(playerc_position3d_t *device,
3063  double ox, double oy, double oz,
3064  double oroll, double opitch, double oyaw);
3065 
3067 PLAYERC_EXPORT int playerc_position3d_reset_odom(playerc_position3d_t *device);
3068 
3070 /**************************************************************************/
3071 
3072 
3073 /***************************************************************************/
3084 typedef struct
3085 {
3088 
3091  int valid;
3092 
3094  double charge;
3095 
3097  double percent;
3098 
3100  double joules;
3101 
3104  double watts;
3105 
3108 
3109 } playerc_power_t;
3110 
3111 
3113 PLAYERC_EXPORT playerc_power_t *playerc_power_create(playerc_client_t *client, int index);
3114 
3116 PLAYERC_EXPORT void playerc_power_destroy(playerc_power_t *device);
3117 
3119 PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access);
3120 
3122 PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device);
3123 
3124 
3126 /**************************************************************************/
3127 
3128 
3129 
3130 /***************************************************************************/
3141 typedef struct
3142 {
3145 
3149  double pan, tilt;
3150 
3152  double zoom;
3153 
3155  int status;
3156 } playerc_ptz_t;
3157 
3158 
3160 PLAYERC_EXPORT playerc_ptz_t *playerc_ptz_create(playerc_client_t *client, int index);
3161 
3163 PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device);
3164 
3166 PLAYERC_EXPORT int playerc_ptz_subscribe(playerc_ptz_t *device, int access);
3167 
3169 PLAYERC_EXPORT int playerc_ptz_unsubscribe(playerc_ptz_t *device);
3170 
3179 PLAYERC_EXPORT int playerc_ptz_set(playerc_ptz_t *device, double pan, double tilt, double zoom);
3180 
3186 PLAYERC_EXPORT int playerc_ptz_query_status(playerc_ptz_t *device);
3187 
3198 PLAYERC_EXPORT int playerc_ptz_set_ws(playerc_ptz_t *device, double pan, double tilt, double zoom,
3199  double panspeed, double tiltspeed);
3200 
3208 PLAYERC_EXPORT int playerc_ptz_set_control_mode(playerc_ptz_t *device, int mode);
3209 
3211 /**************************************************************************/
3212 
3213 /***************************************************************************/
3223 typedef struct
3224 {
3227 
3229  uint32_t element_count;
3230 
3232  double min_angle;
3234  double max_angle;
3236  double angular_res;
3239  double min_range;
3241  double max_range;
3243  double range_res;
3245  double frequency;
3246 
3251  player_bbox3d_t device_size;
3256  player_bbox3d_t *element_sizes;
3257 
3259  uint32_t ranges_count;
3261  double *ranges;
3262 
3268  double *intensities;
3269 
3271  uint32_t bearings_count;
3274  double *bearings;
3275 
3277  uint32_t points_count;
3280 
3282 
3284 PLAYERC_EXPORT playerc_ranger_t *playerc_ranger_create(playerc_client_t *client, int index);
3285 
3287 PLAYERC_EXPORT void playerc_ranger_destroy(playerc_ranger_t *device);
3288 
3290 PLAYERC_EXPORT int playerc_ranger_subscribe(playerc_ranger_t *device, int access);
3291 
3293 PLAYERC_EXPORT int playerc_ranger_unsubscribe(playerc_ranger_t *device);
3294 
3299 PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device);
3300 
3305 PLAYERC_EXPORT int playerc_ranger_power_config(playerc_ranger_t *device, uint8_t value);
3306 
3311 PLAYERC_EXPORT int playerc_ranger_intns_config(playerc_ranger_t *device, uint8_t value);
3312 
3323 PLAYERC_EXPORT int playerc_ranger_set_config(playerc_ranger_t *device, double min_angle,
3324  double max_angle, double angular_res,
3325  double min_range, double max_range,
3326  double range_res, double frequency);
3327 
3338 PLAYERC_EXPORT int playerc_ranger_get_config(playerc_ranger_t *device, double *min_angle,
3339  double *max_angle, double *angular_res,
3340  double *min_range, double *max_range,
3341  double *range_res, double *frequency);
3342 
3344 /**************************************************************************/
3345 
3346 /***************************************************************************/
3357 typedef struct
3358 {
3361 
3364 
3368 
3371 
3373  double *scan;
3374 
3375 } playerc_sonar_t;
3376 
3377 
3379 PLAYERC_EXPORT playerc_sonar_t *playerc_sonar_create(playerc_client_t *client, int index);
3380 
3382 PLAYERC_EXPORT void playerc_sonar_destroy(playerc_sonar_t *device);
3383 
3385 PLAYERC_EXPORT int playerc_sonar_subscribe(playerc_sonar_t *device, int access);
3386 
3388 PLAYERC_EXPORT int playerc_sonar_unsubscribe(playerc_sonar_t *device);
3389 
3395 PLAYERC_EXPORT int playerc_sonar_get_geom(playerc_sonar_t *device);
3396 
3398 /**************************************************************************/
3399 
3400 /***************************************************************************/
3412 typedef struct
3413 {
3415  uint8_t mac[32];
3416 
3418  uint8_t ip[32];
3419 
3421  uint8_t essid[32];
3422 
3424  int mode;
3425 
3427  int encrypt;
3428 
3430  double freq;
3431 
3433  int qual, level, noise;
3434 
3436 
3437 
3439 typedef struct
3440 {
3443 
3446  int link_count;
3447  char ip[32];
3448 } playerc_wifi_t;
3449 
3450 
3452 PLAYERC_EXPORT playerc_wifi_t *playerc_wifi_create(playerc_client_t *client, int index);
3453 
3455 PLAYERC_EXPORT void playerc_wifi_destroy(playerc_wifi_t *device);
3456 
3458 PLAYERC_EXPORT int playerc_wifi_subscribe(playerc_wifi_t *device, int access);
3459 
3461 PLAYERC_EXPORT int playerc_wifi_unsubscribe(playerc_wifi_t *device);
3462 
3464 PLAYERC_EXPORT playerc_wifi_link_t *playerc_wifi_get_link(playerc_wifi_t *device, int link);
3465 
3466 
3468 /**************************************************************************/
3469 
3470 /***************************************************************************/
3482 typedef struct
3483 {
3486 
3488 
3489 
3491 PLAYERC_EXPORT playerc_simulation_t *playerc_simulation_create(playerc_client_t *client, int index);
3492 
3494 PLAYERC_EXPORT void playerc_simulation_destroy(playerc_simulation_t *device);
3495 
3497 PLAYERC_EXPORT int playerc_simulation_subscribe(playerc_simulation_t *device, int access);
3498 
3500 PLAYERC_EXPORT int playerc_simulation_unsubscribe(playerc_simulation_t *device);
3501 
3503 PLAYERC_EXPORT int playerc_simulation_set_pose2d(playerc_simulation_t *device, char* name,
3504  double gx, double gy, double ga);
3505 
3507 PLAYERC_EXPORT int playerc_simulation_get_pose2d(playerc_simulation_t *device, char* identifier,
3508  double *x, double *y, double *a);
3509 
3511 PLAYERC_EXPORT int playerc_simulation_set_pose3d(playerc_simulation_t *device, char* name,
3512  double gx, double gy, double gz,
3513  double groll, double gpitch, double gyaw);
3514 
3516 PLAYERC_EXPORT int playerc_simulation_get_pose3d(playerc_simulation_t *device, char* identifier,
3517  double *x, double *y, double *z,
3518  double *roll, double *pitch, double *yaw, double *time);
3519 
3521 PLAYERC_EXPORT int playerc_simulation_set_property(playerc_simulation_t *device,
3522  char* name,
3523  char* property,
3524  void* value,
3525  size_t value_len);
3526 
3528 PLAYERC_EXPORT int playerc_simulation_get_property(playerc_simulation_t *device,
3529  char* name,
3530  char* property,
3531  void* value,
3532  size_t value_len);
3533 
3535 PLAYERC_EXPORT int playerc_simulation_pause(playerc_simulation_t *device );
3536 
3538 PLAYERC_EXPORT int playerc_simulation_reset(playerc_simulation_t *device );
3539 
3541 PLAYERC_EXPORT int playerc_simulation_save(playerc_simulation_t *device );
3542 
3543 
3545 /***************************************************************************/
3546 
3547 
3548 /**************************************************************************/
3558 typedef struct
3559 {
3563 
3564 
3566 PLAYERC_EXPORT playerc_speech_t *playerc_speech_create(playerc_client_t *client, int index);
3567 
3569 PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device);
3570 
3572 PLAYERC_EXPORT int playerc_speech_subscribe(playerc_speech_t *device, int access);
3573 
3575 PLAYERC_EXPORT int playerc_speech_unsubscribe(playerc_speech_t *device);
3576 
3578 PLAYERC_EXPORT int playerc_speech_say (playerc_speech_t *device, char *);
3579 
3580 
3582 /***************************************************************************/
3583 
3584 /**************************************************************************/
3594 typedef struct
3595 {
3598 
3599  char *rawText;
3600  /* Just estimating that no more than 20 words will be spoken between updates.
3601  Assuming that the longest word is <= 30 characters.*/
3602  char **words;
3603  int wordCount;
3605 
3606 
3609 
3612 
3614 PLAYERC_EXPORT int playerc_speechrecognition_subscribe(playerc_speechrecognition_t *device, int access);
3615 
3618 
3620 /***************************************************************************/
3621 
3622 /**************************************************************************/
3632 typedef struct
3633 {
3635  uint32_t type;
3637  uint32_t guid_count;
3639  uint8_t *guid;
3641 
3643 typedef struct
3644 {
3647 
3649  uint16_t tags_count;
3650 
3653 } playerc_rfid_t;
3654 
3655 
3657 PLAYERC_EXPORT playerc_rfid_t *playerc_rfid_create(playerc_client_t *client, int index);
3658 
3660 PLAYERC_EXPORT void playerc_rfid_destroy(playerc_rfid_t *device);
3661 
3663 PLAYERC_EXPORT int playerc_rfid_subscribe(playerc_rfid_t *device, int access);
3664 
3666 PLAYERC_EXPORT int playerc_rfid_unsubscribe(playerc_rfid_t *device);
3667 
3669 /***************************************************************************/
3670 
3671 /**************************************************************************/
3682 
3684 typedef struct
3685 {
3688 
3690  uint16_t points_count;
3691 
3693  playerc_pointcloud3d_element_t *points;
3695 
3696 
3698 PLAYERC_EXPORT playerc_pointcloud3d_t *playerc_pointcloud3d_create (playerc_client_t *client, int index);
3699 
3701 PLAYERC_EXPORT void playerc_pointcloud3d_destroy (playerc_pointcloud3d_t *device);
3702 
3704 PLAYERC_EXPORT int playerc_pointcloud3d_subscribe (playerc_pointcloud3d_t *device, int access);
3705 
3707 PLAYERC_EXPORT int playerc_pointcloud3d_unsubscribe (playerc_pointcloud3d_t *device);
3708 
3710 /***************************************************************************/
3711 
3712 /**************************************************************************/
3722 
3724 typedef struct
3725 {
3728 
3729  /* Left channel image */
3730  playerc_camera_t left_channel;
3731  /* Right channel image */
3732  playerc_camera_t right_channel;
3733 
3734  /* Disparity image */
3735  playerc_camera_t disparity;
3736 
3737  /* 3-D stereo point cloud */
3738  uint32_t points_count;
3739  playerc_pointcloud3d_stereo_element_t *points;
3740 // player_pointcloud3d_data_t pointcloud;
3742 
3743 
3745 PLAYERC_EXPORT playerc_stereo_t *playerc_stereo_create (playerc_client_t *client, int index);
3746 
3748 PLAYERC_EXPORT void playerc_stereo_destroy (playerc_stereo_t *device);
3749 
3751 PLAYERC_EXPORT int playerc_stereo_subscribe (playerc_stereo_t *device, int access);
3752 
3754 PLAYERC_EXPORT int playerc_stereo_unsubscribe (playerc_stereo_t *device);
3755 
3757 /***************************************************************************/
3758 
3759 /**************************************************************************/
3769 typedef struct
3770 {
3773 
3776  player_pose3d_t vel;
3777  player_pose3d_t acc;
3778 
3781 
3783  float q0, q1, q2, q3;
3784 } playerc_imu_t;
3785 
3787 PLAYERC_EXPORT playerc_imu_t *playerc_imu_create (playerc_client_t *client, int index);
3788 
3790 PLAYERC_EXPORT void playerc_imu_destroy (playerc_imu_t *device);
3791 
3793 PLAYERC_EXPORT int playerc_imu_subscribe (playerc_imu_t *device, int access);
3794 
3796 PLAYERC_EXPORT int playerc_imu_unsubscribe (playerc_imu_t *device);
3797 
3799 PLAYERC_EXPORT int playerc_imu_datatype (playerc_imu_t *device, int value);
3800 
3802 PLAYERC_EXPORT int playerc_imu_reset_orientation (playerc_imu_t *device, int value);
3803 
3805 PLAYERC_EXPORT int playerc_imu_reset_euler(playerc_imu_t *device, float roll, float pitch, float yaw);
3806 
3808 /***************************************************************************/
3809 
3810 /**************************************************************************/
3823 typedef struct
3824 {
3827 
3829  uint32_t node_type;
3831  uint32_t node_id;
3833  uint32_t node_parent_id;
3836 } playerc_wsn_t;
3837 
3838 
3840 PLAYERC_EXPORT playerc_wsn_t *playerc_wsn_create(playerc_client_t *client, int index);
3841 
3843 PLAYERC_EXPORT void playerc_wsn_destroy(playerc_wsn_t *device);
3844 
3846 PLAYERC_EXPORT int playerc_wsn_subscribe(playerc_wsn_t *device, int access);
3847 
3849 PLAYERC_EXPORT int playerc_wsn_unsubscribe(playerc_wsn_t *device);
3850 
3852 PLAYERC_EXPORT int playerc_wsn_set_devstate(playerc_wsn_t *device, int node_id,
3853  int group_id, int devnr, int state);
3854 
3856 PLAYERC_EXPORT int playerc_wsn_power(playerc_wsn_t *device, int node_id, int group_id,
3857  int value);
3858 
3860 PLAYERC_EXPORT int playerc_wsn_datatype(playerc_wsn_t *device, int value);
3861 
3863 PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id,
3864  double frequency);
3865 
3867 /***************************************************************************/
3868 
3869 #ifdef __cplusplus
3870 }
3871 #endif
3872 
3873 #endif
Fiducial finder data.
Definition: playerc.h:1687
Structure describing the WSN node&#39;s data packet.
Definition: player_interfaces.h:4386
PLAYERC_EXPORT int playerc_localize_set_pose(playerc_localize_t *device, double pose[3], double cov[6])
Set the the robot pose (mean and covariance).
Opaque device data.
Definition: playerc.h:2655
double charge
Battery charge (Volts).
Definition: playerc.h:3094
double vel_roll
Angular velocity (radians/sec).
Definition: playerc.h:3001
uint32_t node_parent_id
The ID of the WSN node&#39;s parent (if existing).
Definition: playerc.h:3833
PLAYERC_EXPORT int playerc_ranger_get_geom(playerc_ranger_t *device)
Get the ranger geometry.
int width
Map size, in cells.
Definition: playerc.h:2543
double * ranges
Range data [m].
Definition: playerc.h:3261
Planner device data.
Definition: playerc.h:2704
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:2058
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:3643
Aio proxy data.
Definition: playerc.h:978
player_coopobject_sensor_t * sensor_data
Sensor measurements array.
Definition: playerc.h:1569
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:3449
double gx
Goal location (m, m, radians)
Definition: playerc.h:2719
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:2110
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1447
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:2594
PLAYERC_EXPORT int playerc_client_unsubscribe(playerc_client_t *client, int code, int index)
Unsubscribe a device.
double alt
Altitude (meters).
Definition: playerc.h:1755
Vectormap feature data.
Definition: player.h:265
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:254
Generic message header.
Definition: player.h:161
Data: calibrated IMU data (PLAYER_IMU_DATA_CALIB)
Definition: player_interfaces.h:4724
Note: the structure describing the WSN node&#39;s data packet is declared in Player.
Definition: playerc.h:3823
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:72
struct _playerc_client_t playerc_client_t
Client object data.
PLAYERC_EXPORT int playerc_imu_reset_euler(playerc_imu_t *device, float roll, float pitch, float yaw)
Reset euler orientation.
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:1690
Structure describing a single RFID tag.
Definition: playerc.h:3632
uint8_t state
The gripper&#39;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:1956
PLAYERC_EXPORT int playerc_camera_set_source(playerc_camera_t *device, int source, const char *norm)
Set source channel.
int width
Image dimensions (pixels).
Definition: playerc.h:1450
int pending_count
The number of pending (unprocessed) sensor readings.
Definition: playerc.h:2424
int scan_count
Number of points in the scan.
Definition: playerc.h:2170
A rectangular bounding box, used to define the origin and bounds of an object.
Definition: player.h:307
double px
Odometric pose (m, m, rad).
Definition: playerc.h:2897
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:1780
PLAYERC_EXPORT void playerc_log_destroy(playerc_log_t *device)
Destroy a log proxy.
uint32_t srid
Spatial reference identifier.
Definition: playerc.h:2599
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:2406
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3561
int image_count
Size of image data (bytes)
Definition: playerc.h:1467
player_point_2d_t * point
Scan data; x, y position (m).
Definition: playerc.h:2194
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:2485
player_coopobject_sensor_t * alarm_data
Active alarms array.
Definition: playerc.h:1573
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 void playerc_coopobject_destroy(playerc_coopobject_t *device)
Destroy a cooperating object proxy.
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:1138
double watts
power currently being used (Watts).
Definition: playerc.h:3104
uint32_t alarm_data_count
Number of alarms included.
Definition: playerc.h:1571
PLAYERC_EXPORT int playerc_coopobject_unsubscribe(playerc_coopobject_t *device)
Un-subscribe from the cooperating object device.
PLAYERC_EXPORT int playerc_graphics3d_rotate(playerc_graphics3d_t *device, double a, double x, double y, double z)
Rotate the drawing coordinate system by [a] radians about the vector described by [x...
PLAYERC_EXPORT int playerc_dio_unsubscribe(playerc_dio_t *device)
Un-subscribe from the dio device.
A color descriptor.
Definition: player.h:320
double err_horz
Horizontal and vertical error (meters).
Definition: playerc.h:1774
player_pointcloud3d_stereo_element_t playerc_pointcloud3d_stereo_element_t
Structure describing a single 3D pointcloud element.
Definition: playerc.h:3721
uint8_t motor_state
Reports if the actuators are off (0) or on (1)
Definition: playerc.h:1048
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:3821
double vx
Odometric velocity (m/s, m/s, rad/s).
Definition: playerc.h:2900
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.
PLAYERC_EXPORT int playerc_camera_get_image(playerc_camera_t *device)
Force to get current image.
player_imu_data_calib_t calib_data
Calibrated IMU data (accel, gyro, magnetometer)
Definition: playerc.h:3780
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:1949
PLAYERC_EXPORT void playerc_speech_destroy(playerc_speech_t *device)
Destroy a speech proxy.
Structure describing the cpu.
Definition: player_interfaces.h:4623
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3360
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:4634
int intensity_on
Is intesity data returned.
Definition: playerc.h:2167
struct _playerc_device_t playerc_device_t
Common device info.
playerc_client_t * client
Pointer to the client proxy.
Definition: playerc.h:871
Common device info.
Definition: playerc.h:863
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:3684
double pos_x
Device position (m).
Definition: playerc.h:2992
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:1751
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1881
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:1444
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:2173
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:2716
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&#39;s configuration.
int path_valid
Did the planner find a valid path?
Definition: playerc.h:2710
stereo proxy data.
Definition: playerc.h:3724
Simulation device proxy.
Definition: playerc.h:3482
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:3594
uint32_t user_data_count
User defined message size (in bytes)
Definition: playerc.h:1576
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:3367
int retry_limit
How many times we&#39;ll try to reconnect after a socket error.
Definition: playerc.h:525
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:2603
double pan
The current ptz pan and tilt angles.
Definition: playerc.h:3149
PLAYERC_EXPORT int playerc_device_unsubscribe(playerc_device_t *device)
Unsubscribe the device.
PLAYERC_EXPORT int playerc_graphics3d_draw(playerc_graphics3d_t *device, player_graphics3d_draw_mode_t mode, player_point_3d_t pts[], int count)
Draw some points in the given mode.
uint16_t points_count
The number of 3D pointcloud elementS found.
Definition: playerc.h:3690
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&#39;re currently connected.
Definition: playerc.h:520
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:488
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:2185
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:3271
A pose in the plane.
Definition: player.h:217
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:3268
uint8_t * bumpers
Bump data: unsigned char, either boolean or code indicating corner.
Definition: playerc.h:1404
double min_right
Minimum range, in meters, in the right half of the scan (those ranges from the first beam...
Definition: playerc.h:2210
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.
Definition: player_interfaces.h:5473
double min_angle
Start angle of scans [rad].
Definition: playerc.h:3232
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:3144
player_color_t color
current drawing color
Definition: playerc.h:1817
PLAYERC_EXPORT int playerc_position1d_set_odom(playerc_position1d_t *device, double odom)
Set the odometry offset.
Graphics3d device data.
Definition: playerc.h:1878
player_health_memory_t mem
The memory stats.
Definition: playerc.h:2024
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:3646
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:2661
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1230
int type
What kind of log device is this? Either PLAYER_LOG_TYPE_READ or PLAYER_LOG_TYPE_WRITE.
Definition: playerc.h:2481
double pos
Odometric pose [m] or [rad].
Definition: playerc.h:2803
#define PLAYER_MAX_DEVICES
The maximum number of devices the server will support.
Definition: player.h:74
An angle in 3D space.
Definition: player.h:206
PLAYERC_EXPORT int playerc_coopobject_send_data(playerc_coopobject_t *device, int node_id, int source_id, int data_type, int data_size, unsigned char *extradata)
Send data to cooperating object.
PLAYERC_EXPORT void playerc_blobfinder_destroy(playerc_blobfinder_t *device)
Destroy a blobfinder proxy.
double frequency
Scanning frequency [Hz].
Definition: playerc.h:3245
PLAYERC_EXPORT int playerc_planner_subscribe(playerc_planner_t *device, int access)
Subscribe to the planner device.
PLAYERC_EXPORT int playerc_coopobject_subscribe(playerc_coopobject_t *device, int access)
Subscribe to the cooperating object 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:1393
Power device data.
Definition: playerc.h:3084
PLAYERC_EXPORT int playerc_client_disconnect(playerc_client_t *client)
Disconnect from the server.
Blinklight proxy data.
Definition: playerc.h:1288
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:145
PLAYERC_EXPORT playerc_blobfinder_t * playerc_blobfinder_create(playerc_client_t *client, int index)
Create a blobfinder proxy.
uint8_t request
Request type.
Definition: playerc.h:1583
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.
uint8_t origin
The type of Cooperating Object.
Definition: playerc.h:1544
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:2806
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2155
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2888
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:2540
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:3100
int valid
status bits.
Definition: playerc.h:3091
double utc_time
UTC time (seconds since the epoch)
Definition: playerc.h:1746
PLAYERC_EXPORT int playerc_power_unsubscribe(playerc_power_t *device)
Un-subscribe from the power device.
Gripper device data.
Definition: playerc.h:1934
int map_size_x
Map dimensions (cells).
Definition: playerc.h:2412
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&#39;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_STATE)
Definition: player_interfaces.h:4072
Structure containing a single actuator&#39;s information.
Definition: player_interfaces.h:3793
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:2534
double max_range
Maximum range [m].
Definition: playerc.h:3241
PLAYERC_EXPORT int playerc_client_peek(playerc_client_t *client, int timeout)
Test to see if there is pending data.
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:3107
Request/reply: get geometry.
Definition: player_interfaces.h:4147
double max_angle
End angle of scans [rad].
Definition: playerc.h:3234
Position3d device data.
Definition: playerc.h:2980
playerc_putmsg_fn_t putmsg
Standard message callback for this device.
Definition: playerc.h:903
Info about an available (but not necessarily subscribed) device.
Definition: playerc.h:494
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:2430
player_color_t color
current drawing color
Definition: playerc.h:1884
double range_res
Range resolution [m].
Definition: playerc.h:3243
PLAYERC_EXPORT int playerc_power_subscribe(playerc_power_t *device, int access)
Subscribe to the power device.
PLAYERC_EXPORT int playerc_coopobject_send_position(playerc_coopobject_t *device, uint16_t node_id, uint16_t source_id, player_pose2d_t pos, uint8_t status)
Send data to cooperating object.
PLAYERC_EXPORT int playerc_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:560
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:896
player_audio_seq_t seq_data
last block of seq data
Definition: playerc.h:1141
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:5165
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:184
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:1135
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:513
Ranger proxy data.
Definition: playerc.h:3223
int8_t * map_cells
Map data (empty = -1, unknown = 0, occupied = +1).
Definition: playerc.h:2421
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:3772
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:3250
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1038
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:3639
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:552
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:2415
player_vectormap_layer_info_t ** layers_info
Layer info.
Definition: playerc.h:2607
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:887
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:1777
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:2556
uint8_t command
Command type.
Definition: playerc.h:1581
double max_range
Maximum range of sensor, in m.
Definition: playerc.h:2182
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&#39;s store - if 0, the gripper cannot store.
Definition: playerc.h:1951
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3687
uint16_t id
Cooperating Object ID.
Definition: playerc.h:1546
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:2115
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:884
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:3141
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:1401
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:868
int stall
Stall flag [0, 1].
Definition: playerc.h:2903
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:532
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:1499
Hypothesis data.
Definition: playerc.h:2398
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:1743
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2983
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:2176
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:2713
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:3236
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:3826
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:2188
double range_res
Range resolution, in m.
Definition: playerc.h:2179
Speech proxy data.
Definition: playerc.h:3558
PLAYERC_EXPORT void playerc_position2d_destroy(playerc_position2d_t *device)
Destroy a position2d device proxy.
Position1d device data.
Definition: playerc.h:2791
uint32_t actuators_count
The number of actuators in the array.
Definition: playerc.h:1041
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:3485
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:2794
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:564
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:1765
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:2202
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:1740
PLAYERC_EXPORT int playerc_wsn_datafreq(playerc_wsn_t *device, int node_id, int group_id, double frequency)
Change data delivery frequency.
PLAYERC_EXPORT int playerc_camera_get_source(playerc_camera_t *device)
Get source channel (sets norm and source fields in the current proxy data).
uint32_t beams
The position of the object in the gripper.
Definition: playerc.h:1958
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:1129
player_pose3d_t pose
Gripper geometry in the robot cs: pose gives the position and orientation, outer_size gives the exten...
Definition: playerc.h:1945
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:2061
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:3775
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:3357
Note: the structure describing the HEALTH&#39;s data packet is declared in Player.
Definition: playerc.h:2017
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1814
uint32_t element_count
Number of individual elements in the device.
Definition: playerc.h:3229
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:3152
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:1960
uint8_t mode
Definition: playerc.h:539
unsigned int blobs_count
A list of detected blobs.
Definition: playerc.h:1353
playerc_rfidtag_t * tags
The list of RFID tags.
Definition: playerc.h:3652
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3727
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:3681
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:900
PLAYERC_EXPORT typedef void(* playerc_putmsg_fn_t)(void *device, char *header, char *data)
Typedef for proxy callback function.
Definition: playerc.h:485
uint32_t intensities_count
Number of intensities in a scan.
Definition: playerc.h:3264
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:1696
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:1937
Vectormap data.
Definition: player_interfaces.h:5176
Blobfinder device data.
Definition: playerc.h:1344
int curr_waypoint
Current waypoint index (handy if you already have the list of waypoints).
Definition: playerc.h:2727
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:3597
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2537
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:3155
int fresh
Freshness flag.
Definition: playerc.h:892
player_health_memory_t swap
The swap stats.
Definition: playerc.h:2026
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1291
uint8_t * user_data
User defined data array.
Definition: playerc.h:1578
PLAYERC_EXPORT int playerc_opaque_req(playerc_opaque_t *device, player_opaque_data_t *request, player_opaque_data_t **reply)
Send a generic request.
uint32_t parameters_count
Request/command parameters array size (in bytes)
Definition: playerc.h:1585
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:2215
Graphics2d device data.
Definition: playerc.h:1811
int fiducials_count
List of detected beacons.
Definition: playerc.h:1699
uint32_t ranges_count
Number of ranges in a scan.
Definition: playerc.h:3259
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:2022
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2020
player_point_3d_t * points
Scan points (x, y, z).
Definition: playerc.h:3279
uint32_t type
Tag type.
Definition: playerc.h:3635
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1641
playerc_wifi_link_t * links
A list containing info for each link.
Definition: playerc.h:3445
double * scan
Scan data: range (m).
Definition: playerc.h:3373
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:3637
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:1453
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:1390
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.
Note: the structure describing the Cooperating Object&#39;s data packet is declared in Player...
Definition: playerc.h:1531
PLAYERC_EXPORT int playerc_position1d_enable(playerc_position1d_t *device, int enable)
Enable/disable the motors.
Bumper proxy data.
Definition: playerc.h:1387
int8_t data_range
Value for each cell (-range <= EMPTY < 0, unknown = 0, 0 < OCCUPIED <= range)
Definition: playerc.h:2549
Log proxy data.
Definition: playerc.h:2474
int sock
Definition: playerc.h:536
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:1768
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.
PLAYERC_EXPORT int playerc_coopobject_send_cmd(playerc_coopobject_t *device, int node_id, int source_id, int cmd, int parameters_size, unsigned char *parameters)
Send command to cooperating object.
float q0
Orientation data as quaternions.
Definition: playerc.h:3783
uint16_t parent_id
Cooperating Object Parent ID (if existing)
Definition: playerc.h:1548
int laser_id
Laser IDentification information.
Definition: playerc.h:2205
Request/reply: get pose.
Definition: player_interfaces.h:2130
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&#39;s data delivery mode.
playerwkbprocessor_t wkbprocessor
WKB processor instance if you want to deal with WKB data.
Definition: playerc.h:2609
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2707
PLAYERC_EXPORT void playerc_ptz_destroy(playerc_ptz_t *device)
Destroy a ptz proxy.
Structure describing a single blob.
Definition: player_interfaces.h:1068
int callback_count
Extra callbacks for this device.
Definition: playerc.h:909
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:570
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3087
Client object data.
Definition: playerc.h:506
int compression
Image compression method.
Definition: playerc.h:1464
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2477
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:4861
PLAYERC_EXPORT void playerc_position3d_destroy(playerc_position3d_t *device)
Destroy a position3d device proxy.
Position2d device data.
Definition: playerc.h:2885
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:2152
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:2658
PLAYERC_EXPORT int playerc_graphics2d_draw_multiline(playerc_graphics2d_t *device, player_point_2d_t pts[], int count)
Draw a set of lines whose end points are at pts[2n] and pts[2n+1].
PLAYERC_EXPORT playerc_coopobject_t * playerc_coopobject_create(playerc_client_t *client, int index)
Create a cooperating object proxy.
uint8_t * image
Image data (byte aligned, row major order).
Definition: playerc.h:1473
joystick proxy data.
Definition: playerc.h:2107
int map_tile_x
Next map tile to read.
Definition: playerc.h:2418
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:543
int scan_count
Number of points in the scan.
Definition: playerc.h:3370
double pos_roll
Device orientation (radians).
Definition: playerc.h:2995
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:3649
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:1638
A pose in space.
Definition: player.h:228
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:1714
uint32_t points_count
Number of scan points.
Definition: playerc.h:3277
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:1045
uint8_t * data
Data.
Definition: playerc.h:2664
player_pose3d_t * element_poses
Geometry of each individual element in the device (e.g.
Definition: playerc.h:3255
uint32_t node_type
The type of WSN node.
Definition: playerc.h:3829
IMU proxy state data.
Definition: playerc.h:3769
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 unsigned playerc_camera_get_pixel_component(playerc_camera_t *device, unsigned int x, unsigned int y, int component)
Get given component of given pixel.
PLAYERC_EXPORT 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:3097
uint32_t node_id
The ID of the WSN node.
Definition: playerc.h:3831
double lasttime
Server time stamp on the previous packet.
Definition: playerc.h:572
PLAYERC_EXPORT int playerc_client_read_nonblock(playerc_client_t *client)
Read and process a packet (nonblocking)
int data_received
Definition: playerc.h:547
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:2601
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:1398
player_audio_mixer_channel_list_t mixer_data
current channel data
Definition: playerc.h:1144
A point in 3D space.
Definition: player.h:194
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:2730
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:1685
void * user_data
Extra user data for this device.
Definition: playerc.h:906
uint8_t * parameters
Request/command parameters array.
Definition: playerc.h:1587
double vdop
Vertical dilution of precision.
Definition: playerc.h:1771
char * cells
Occupancy for each cell.
Definition: playerc.h:2552
Definition: playerc.h:437
double pending_time
The timestamp on the last reading processed.
Definition: playerc.h:2427
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&#39;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:1227
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:1050
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:3239
char drivername[PLAYER_MAX_DRIVER_STRING_LEN]
The driver name.
Definition: playerc.h:877
double retry_time
How long to sleep, in seconds, to sleep between reconnect attempts.
Definition: playerc.h:529
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:1463
int pose_count
Number of pose values.
Definition: playerc.h:3363
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_EXPORT int playerc_coopobject_send_req(playerc_coopobject_t *device, int node_id, int source_id, int req, int parameters_size, unsigned char *parameters)
Send request to cooperating object.
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1347
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:3004
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_planner_set_cmd_start(playerc_planner_t *device, double sx, double sy, double sa)
Set the start pose (sx, sy, sa)
PLAYERC_EXPORT int playerc_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.
int messageType
Flag to indicate that new info has come.
Definition: playerc.h:1537
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2597
void * py_private
Kludge to get around python callback issues.
Definition: playerc.h:1234
int * intensity
Scan reflection intensity values (0-3).
Definition: playerc.h:2199
int subscribed
The subscribe flag is non-zero if the device has been successfully subscribed (read-only).
Definition: playerc.h:881
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.
double waypoint_distance
Straight-line distance along allwaypoints in the current plan.
Definition: playerc.h:2738
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.
double course
Course made good (heading if the robot moves along its longitudinal axis), in radians.
Definition: playerc.h:1762
PLAYERC_EXPORT void playerc_camera_copy_image(playerc_camera_t *device, void *dst, size_t dst_size)
Copy image to some pre-allocated place.
double speed
Speed over ground, in m/s.
Definition: playerc.h:1758
void * id
A useful ID for identifying devices; mostly used by other language bindings.
Definition: playerc.h:510
PLAYERC_EXPORT void playerc_imu_destroy(playerc_imu_t *device)
Destroy a imu proxy.
unsigned int width
Image dimensions (pixels).
Definition: playerc.h:1350
uint32_t sensor_data_count
Number of sensors included.
Definition: playerc.h:1567
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:2722
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:1456
Wifi device proxy.
Definition: playerc.h:3439
float x
Cooperating Object Position.
Definition: playerc.h:1560
player_devaddr_t addr
Player id of the device.
Definition: playerc.h:497
player_vectormap_layer_data_t ** layers_data
Layer data.
Definition: playerc.h:2605
PLAYERC_EXPORT void playerc_speechrecognition_destroy(playerc_speechrecognition_t *device)
Destroy a speech recognition proxy.
Player mixer channels.
Definition: player_interfaces.h:1569
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:3274
playerc_pointcloud3d_element_t * points
The list of 3D pointcloud elements.
Definition: playerc.h:3693
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:1132
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_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:1534
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:291
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:981
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:3226
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&#39;s data packet.
Definition: playerc.h:3835
The geometry of a single bumper.
Definition: player_interfaces.h:1931
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:1461
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:3442
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:874
Limb device data.
Definition: playerc.h:2324
double vel_x
Linear velocity (m/s).
Definition: playerc.h:2998
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:2409
playerc_device_t info
Device info; must be at the start of all device structures.
Definition: playerc.h:2327
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:429
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.
uint16_t RSSIsender
Cooperating Object data packet.
Definition: playerc.h:1553
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:1147
PLAYERC_EXPORT int playerc_planner_unsubscribe(playerc_planner_t *device)
Un-subscribe from the planner device.
Player mixer channels.
Definition: player_interfaces.h:1530
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:2809
Definition: player_interfaces.h:5284
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:1043
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:2822
PLAYERC_EXPORT int playerc_ir_get_geom(playerc_ir_t *device)
Get the ir geometry.
Hypothesis format.
Definition: player_interfaces.h:2335
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:1052
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:1035
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.