-
Notifications
You must be signed in to change notification settings - Fork 54
/
Copy pathPozyx.h
1870 lines (1692 loc) · 80.6 KB
/
Pozyx.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
/**
* Pozyx.h
* -------
* This file is a definition of all structures, classes and functions used in the
* Pozyx environment.
*
* Each function is described:
* - which input parameters are expected
- what is the behaviour
- and what is the expected output
*
*/
#ifndef POZYX_h
#define POZYX_h
#include <inttypes.h>
#if (ARDUINO >= 100)
#include "Arduino.h"
#else
#include "WProgram.h"
#endif
#undef NULL
#define NULL 0
///////////////////////////////////////////////// ASSERTIONS /////////////////////////////////////
// assertions will check for wrong use of the library.
// Define NDEBUG to remove the assertions: this will reduce codesize. Do this in your production code.
//#define NDEBUG
// enable printing of function name, filename, linenumber and failed expression. This takes a LOT of memory (too much for the Arduino UNO)
//#define __ASSERT_USE_STDERR
#include <assert.h>
// overwrite the assertions to reduce codesize.
#if ! defined(NDEBUG) && ! defined(__ASSERT_USE_STDERR)
#undef assert
#define assert(e) ((e) ? (void)0 : \
__assert_pozyx(__func__, __FILE__, __LINE__))
extern void __assert_pozyx(const char *__func, const char *__file, int __lineno);
#endif
////////////////////////////////////////// END OF ASSERTIONS /////////////////////////////////////
extern "C" {
#include "Pozyx_definitions.h"
}
typedef float float32_t;
/**
* The UWB settings type defines all attributes needed to set the UWB (communication) parameters
*/
typedef struct _UWB_settings {
/** The UWB channel number. Possible values are 1, 2, 3, 4, 5, 7. See the reg:POZYX_UWB_CHANNEL register for more information. */
uint8_t channel;
/** The bitrate. Possible values are
*
* - 0: 110kbits/s
* - 1: 850kbits/s
* - 2: 6.8Mbits/s.
*
* See the reg:POZYX_UWB_RATES register for more information */
uint8_t bitrate;
/** The UWB pulse repetition frequency (PRF). Possible values are
*
* - 1: 16MHz
* - 2: 64MHz
*
* See the reg:POZYX_UWB_RATES register for more information */
uint8_t prf;
/** The preabmle length. Possible values are:
*
* - 0x0C : 4096 symbols.
* - 0x28 : 2048 symbols.
* - 0x18 : 1536 symbols.
* - 0x08 : 1024 symbols.
* - 0x34 : 512 symbols.
* - 0x24 : 256 symbols.
* - 0x14 : 128 symbols.
* - 0x04 : 64 symbols.
*
* See the reg:POZYX_UWB_PLEN register for more information.
*/
uint8_t plen;
/** The transmission gain in dB. Possible values are between 0dB and 33.5dB, with a resolution of 0.5dB. See the reg:POZYX_UWB_GAIN register for more information.*/
float gain_db;
}UWB_settings_t;
/**
* The coordinates type defines the coordinates of position result or anchor location
*/
typedef struct __attribute__((packed))_coordinates {
/** The x-coordinate in mm */
int32_t x;
/** The y-coordinate in mm */
int32_t y;
/** The z-coordinate in mm */
int32_t z;
}coordinates_t;
/**
* A structure representing a 3D vector with floating points.
* This type is used to represent most of the sensor values that have components in 3 dimensions.
*/
typedef struct __attribute__((packed))_v3D_float32 {
/** The x-coordinate of the vector */
float32_t x;
/** The y-coordinate of the vector */
float32_t y;
/** The z-coordinate of the vector */
float32_t z;
}v3D_float32_t;
// some supporting types for specific sensors
typedef v3D_float32_t acceleration_t;
typedef v3D_float32_t magnetic_t;
typedef v3D_float32_t angular_vel_t;
typedef v3D_float32_t linear_acceleration_t;
typedef v3D_float32_t gravity_vector_t;
/**
* The position error type gives the resulting error covariance for a given position result
*/
typedef struct __attribute__((packed))_pos_error {
/** The variance in the x-coordinate */
int16_t x;
/** The variance in the y-coordinate */
int16_t y;
/** The variance in the z-coordinate */
int16_t z;
/** The covariance of xy */
int16_t xy;
/** The covariance of xz */
int16_t xz;
/** The covariance of yz */
int16_t yz;
}pos_error_t;
/**
* The euler angles type holds the absolute orientation of the pozyx device using the Euler angles (yaw, pitch, roll) representation
*/
typedef struct __attribute__((packed))_euler_angles {
/** The heading (yaw) in degrees. */
float32_t heading;
/** The roll in degrees. */
float32_t roll;
/** The pitch in degrees. */
float32_t pitch;
}euler_angles_t;
/**
* The quaternion_t type holds the absolute orientation of the pozyx device using the a quaternion representation
*/
typedef struct __attribute__((packed))_quaternion {
/** weight of the quaterion. */
float32_t weight;
/** x-coordinate of the quaterion. */
float32_t x;
/** y-coordinate of the quaterion. */
float32_t y;
/** z-coordinate of the quaterion. */
float32_t z;
}quaternion_t;
/**
* raw sensor data. This follows the ordering of the pozyx registers
*/
typedef struct __attribute__((packed))_sensor_raw {
uint32_t pressure;
int16_t acceleration[3];
int16_t magnetic[3];
int16_t angular_vel[3];
int16_t euler_angles[3];
int16_t quaternion[4];
int16_t linear_acceleration[3];
int16_t gravity_vector[3];
uint8_t temperature;
}sensor_raw_t;
/**
* The sensor data type allows to read the whole sensor data in one datastructure with one call
*/
typedef struct __attribute__((packed))_sensor_data {
float32_t pressure;
acceleration_t acceleration;
magnetic_t magnetic;
angular_vel_t angular_vel;
euler_angles_t euler_angles;
quaternion_t quaternion;
linear_acceleration_t linear_acceleration;
gravity_vector_t gravity_vector;
float32_t temperature;
}sensor_data_t;
/**
* The device_coordinates_t type is used to describe a pozyx device required for the device list
*/
typedef struct __attribute__((packed))_device_coordinates {
/** the unique 16-bit network id (by default this is the same as on the label of the device) */
uint16_t network_id;
/** a flag indicating some aspects of the device such as anchor or tag.
* Possible values are:
*
* - 1 : anchor
* - 2 : tag
*/
uint8_t flag;
/** The coordinates of the device */
coordinates_t pos;
}device_coordinates_t;
/**
* The device range type stores all the attributes linked to a range measurement
*/
typedef struct __attribute__((packed))_device_range {
/** The timestamp in ms of the range measurement. */
uint32_t timestamp;
/** The distance in mm. */
uint32_t distance;
/** The received signal strength in dBm. */
int16_t RSS;
}device_range_t;
/**
* Provides an interface to an attached Pozyx shield.
*
*/
class PozyxClass
{
protected:
static int _mode; // the mode of operation, can be MODE_INTERRUPT or MODE_POLLING
static int _interrupt; // variable to indicate that an interrupt has occured
static int _hw_version; // Pozyx harware version
static int _fw_version; // Pozyx software (firmware) version. (By updating the firmware on the Pozyx device, this value can change)
/**
* Function: i2cWriteWrite
* -----------------------
* Internal function that writes a number of bytes to a specfified Pozyx register
* This function implements the I2C interface as described in the datasheet on our website
* Input values:
* @param reg_address Pozyx address to write to
* @param pData reference to the data that needs to be writen
* @param size size in byte of data to be written
*
* @return
* #POZYX_FAILURE: error occured during the process
* #POZYX_SUCCESS: successful execution of the function
*/
static int i2cWriteWrite(const uint8_t reg_address, const uint8_t *pData, int size);
/**
* Function: i2cWriteRead
* ----------------------
* Internal function that writes and reads a number of bytes to call a specfic Pozyx register function
* This function implements the I2C interface as described in the datasheet on our website
* Input values:
* @param write_data reference to the data that needs to be writen
* @param write_len size in byte of data to be written
* @param read_data reference to the pointer where the read data should be stored
* @param read_len size in byte of data to be read
*
* @return
* POZYX_FAILURE: error occured during the process
* POZYX_SUCCESS: successful execution of the function
*/
static int i2cWriteRead(uint8_t* write_data, int write_len, uint8_t* read_data, int read_len);
/**
* Function: void IRQ
* ------------------
* Internal function that sets the _interrupt variable on an Arduino interrupt
*/
static void IRQ();
/**
* This function calls the waitForFlag function in polling mode. After this, the previous mode is reset.
*
* @param interrupt_flag the exepected Pozyx interrupt. Possible values are #POZYX_INT_STATUS_ERR,
* #POZYX_INT_STATUS_POS, #POZYX_INT_STATUS_IMU, #POZYX_INT_STATUS_RX_DATA, #POZYX_INT_STATUS_FUNC, or combinations.
* @param timeout_ms maximum waiting time in milliseconds for flag to occur
* @param interrupt a pointer that will contain the value of the interrupt status register
*
* @retval #true event occured.
* @retval #false event did not occur, this function timed out.
*/
public:
static boolean waitForFlag_safe(uint8_t interrupt_flag, int timeout_ms, uint8_t *interrupt = NULL);
/**
* Read from the registers of the connected Pozyx shield.
*
* @param reg_address: the specific register address to start reading from
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes to read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int regRead(uint8_t reg_address, uint8_t *pData, int size);
/**
* Write to the registers of the connected Pozyx shield.
*
* @param reg_address: the specific register address to start writing to
* @param pData: a pointer to the data thas will be written
* @param size: the number of bytes to write
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int regWrite(uint8_t reg_address, uint8_t *pData, int size);
/**
* Call a register funcion on the connected Pozyx shield.
*
* @param reg_address: the specific register address of the function
* @param params: this is the pointer to a parameter array required for the specific function that is called
* @param param_size: the number of bytes in the params array
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes that will be stored in pData
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int regFunction(uint8_t reg_address, uint8_t *params=NULL, int param_size=0, uint8_t *pData=NULL, int size=0);
/**
* Write to the registers on a remote Pozyx device (anchor or tag).
*
* @param destination: this is the network id of the receiving Pozyx tag
* @param reg_address: the specific register address to start writing to
* @param pData: a pointer to the data thas will be written
* @param size: the number of bytes to write
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int remoteRegWrite(uint16_t destination, uint8_t reg_address, uint8_t *pData, int size);
/**
* Read from the registers on a remote Pozyx device (anchor or tag).
*
* @param destination: this is the network id of the receiving Pozyx tag
* @param reg_address: the specific register address to start reading from
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes to read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int remoteRegRead(uint16_t destination, uint8_t reg_address, uint8_t *pData, int size);
/**
* Call a register funcion on a remote Pozyx device (anchor or tag).
*
* @param destination: this is the network id of the receiving Pozyx tag
* @param reg_address: the specific register address of the function
* @param params: this is the pointer to a parameter array required for the specific function that is called
* @param param_size: the number of bytes in the params array
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes that will be stored in pData
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int remoteRegFunction(uint16_t destination, uint8_t reg_address, uint8_t *params=NULL, int param_size=0, uint8_t *pData=NULL, int size=0);
/** \addtogroup core
* @{
*/
/**
* Wait until the Pozyx shields has raised a specfic event flag or until timeout.
* This functions halts the process flow until a specific event flag was raised by the Pozyx
* shield. The event flag is checked by reading the contents of the reg:POZYX_INT_STATUS register.
* This function can work in both polled and interupt mode
*
* @param interrupt_flag the exepected Pozyx interrupt. Possible values are #POZYX_INT_STATUS_ERR,
* #POZYX_INT_STATUS_POS, #POZYX_INT_STATUS_IMU, #POZYX_INT_STATUS_RX_DATA, #POZYX_INT_STATUS_FUNC, or combinations.
* @param timeout_ms maximum waiting time in milliseconds for flag to occur
* @param interrupt a pointer that will contain the value of the interrupt status register
*
* @retval #true event occured.
* @retval #false event did not occur, this function timed out.
*/
static int remoteRegFunctionWithoutCheck(uint16_t destination, uint8_t reg_address, uint8_t *params=NULL, int param_size=0, uint8_t *pData=NULL, int size=0);
/** \addtogroup core
* @{
*/
/**
* Does the same as the remoteRegFunction, but doesn't wait for nearly as long and doesn't care about whether the function worked.
*
* @param interrupt_flag the exepected Pozyx interrupt. Possible values are #POZYX_INT_STATUS_ERR,
* #POZYX_INT_STATUS_POS, #POZYX_INT_STATUS_IMU, #POZYX_INT_STATUS_RX_DATA, #POZYX_INT_STATUS_FUNC, or combinations.
* @param timeout_ms maximum waiting time in milliseconds for flag to occur
* @param interrupt a pointer that will contain the value of the interrupt status register
*
* @retval #true event occured.
* @retval #false event did not occur, this function timed out.
*/
static boolean waitForFlag(uint8_t interrupt_flag, int timeout_ms, uint8_t *interrupt = NULL);
/**
* Initiates the Pozyx shield. This function initializes the pozyx device.
* It will verify that the device is functioning correctly by means of the self-test, and it will configure the interrupts.
* See the register reg:POZYX_INT_MASK for more details about the interrupts.
*
* @param print_result outputs the result of the function to the Serial output
* @param mode The modus of the system: #MODE_POLLING or #MODE_INTERRUPT
* @param interrupts defines which events trigger interrupts. This field is only required for #MODE_INTERRUPT. Possible
* values are bit-wise combinations of #POZYX_INT_MASK_ERR, #POZYX_INT_MASK_POS, #POZYX_INT_MASK_IMU, #POZYX_INT_MASK_RX_DATA and #POZYX_INT_MASK_FUNC. Use #POZYX_INT_MASK_ALL to trigger on all events.
* @param interrupt_pin Pozyx interrupt pin: #POZYX_INT_PIN0 or #POZYX_INT_PIN1. This field is only required for #MODE_INTERRUPT.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int begin(boolean print_result = false, int mode = MODE_INTERRUPT, int interrupts = POZYX_INT_MASK_ALL, int interrupt_pin = POZYX_INT_PIN0);
/**
* Read from the registers on a local or remote Pozyx device (anchor or tag).
*
* @param reg_address: the specific register address to start reading from
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes to read
* @param remote_id: this is the network id of the remote Pozyx tag, if used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getRead(uint8_t reg_address, uint8_t *pData, int size, uint16_t remote_id=NULL);
/**
* Write to the registers of a local remote Pozyx device (anchor or tag).
*
* @param reg_address: the specific register address to start writing to
* @param pData: a pointer to the data thas will be written
* @param size: the number of bytes to write
* @param remote_id: this is the network id of the remote Pozyx tag, if used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setWrite(uint8_t reg_address, uint8_t *pData, int size, uint16_t remote_id=NULL);
/**
* Call a register funcion on a local or remote Pozyx device (anchor or tag).
*
* @param reg_address: the specific register address of the function
* @param params: this is the pointer to a parameter array required for the specific function that is called
* @param param_size: the number of bytes in the params array
* @param pData: a pointer to the data thas will be read
* @param size: the number of bytes that will be stored in pData
* @param remote_id: this is the network id of the remote Pozyx tag, if used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int useFunction(uint8_t reg_address, uint8_t *params=NULL, int param_size=0, uint8_t *pData=NULL, int size=0, uint16_t remote_id=NULL);
/** @}*/
// currently groupless TODO
/** \addtogroup communication_functions
* @{
*/
/**
* Wirelessly transmit data to a remote pozyx device.
* This function combines writeTXBufferData and sendTXBufferData to write data to the transmit buffer and immediately transmit it.
*
* @param destination the network id of the device that should receive the data. A value of 0 will result in a broadcast
* @param pData pointer to the data that should be transmitted
* @param size number of bytes to transmit
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int sendData(uint16_t destination, uint8_t *pData, int size);
/**
* Write data bytes in the transmit buffer.
* This function writes bytes in the transmit buffer without sending it yet.
*
* @param data[] the array with data bytes
* @param size size of the data array
* @param offset The offset in the memory
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*
* @see sendTXBufferData
*/
static int writeTXBufferData(uint8_t data[], int size, int offset = 0);
/**
* Wirelessly transmit data.
* Wirelessly transmit the contents of the transmit buffer over UWB.
*
* @param destination the network id of the device that should receive the data. A value of 0 will result in a broadcast.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*
* @see writeTXBufferData
*/
static int sendTXBufferData(uint16_t destination = 0x0);
/**
* Read data bytes from receive buffer.
* This function reads the bytes from the receive buffer from the last received message.
*
* @param pData pointer to where the data will be stored
* @param size the number of bytes to read from the receive buffer.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*
* @see getLastDataLength getLastNetworkId
*/
static int readRXBufferData(uint8_t* pData, int size);
/**
* Obtain the network id of the last message.
* This function identifies the source of the last message that was wirelessly received.
*
* @param network_id: the pointer that stores the network_id
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getLastNetworkId(uint16_t *network_id, uint16_t remote_id = NULL);
/**
* Obtain the number of bytes received.
* This function gives the number of bytes in the last message that was wirelessly received.
*
* @param data_length: the pointer that stores the number of received bytes
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getLastDataLength(uint8_t *data_length, uint16_t remote_id = NULL);
/**
* Obtain the network id of the connected Pozyx device.
* The network id is a unique 16bit identifier determined based on the hardware components. When the system is reset the orignal value is restored
*
* @param network_id: reference to the network_id pointer to store the data
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int getNetworkId(uint16_t *network_id);
/**
* Overwrite the network id.
* This function overwrites the network id of the pozyx device either locally or remotely. The network id must be unique within a network.
* When the system is reset the orignal network id is restored.
*
* @param network_id: the new network id
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setNetworkId(uint16_t network_id, uint16_t remote_id = NULL);
/**
* Obtain the current UWB settings.
* Functions to retrieve the current UWB settings. In order to communicate, two pozyx devices must have exactly the same UWB settings.
*
* @param UWB_settings reference to the UWB settings object to store the data
* @param remote_id optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getUWBSettings(UWB_settings_t *UWB_settings, uint16_t remote_id = NULL);
/**
* Overwrite the UWB settings.
* This function overwrites the UWB settings such as UWB channel, gain, PRF, etc.
* In order to communicate, two pozyx devices must have exactly the same UWB settings.
* Upon reset, the default UWB settings will be loaded.
*
* @param UWB_settings reference to the new UWB settings. If the gain_db is set to 0, it will automatically load the default gain value for the given uwb paramters.
* @param remote_id optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setUWBSettings(UWB_settings_t *UWB_settings, uint16_t remote_id = NULL);
/**
* Overwrite the UWB settings except the gain.
* This function overwrites the UWB settings such as UWB channel, PRF, etc.
* In order to communicate, two pozyx devices must have exactly the same UWB settings.
* Upon reset, the default UWB settings will be loaded.
*
* @param UWB_settings reference to the new UWB settings. If the gain_db is set to 0, it will automatically load the default gain value for the given uwb paramters.
* @param remote_id optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setUWBSettingsExceptGain(UWB_settings_t *UWB_settings, uint16_t remote_id=NULL);
/**
* Set the Ultra-wideband frequency channel.
* This function sets the ultra-wideband (UWB) frequency channel used for transmission and reception.
* For wireless communication, both the receiver and transmitter must be on the same UWB channel.
* More information can be found in the register reg:POZYX_UWB_CHANNEL.
*
* @param channel_num the channel number, possible values are 1, 2, 3, 4, 5 and 7.
* @param remote_id optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
*/
static int setUWBChannel(int channel_num, uint16_t remote_id = NULL);
/**
* Get the Ultra-wideband frequency channel.
* This function reads the ultra-wideband (UWB) frequency channel used for transmission and reception.
* For wireless communication, both the receiver and transmitter must be on the same UWB channel.
* More information can be found in the register reg:POZYX_UWB_CHANNEL.
*
* @param channel_num the channel number currently set, possible values are 1, 2, 3, 4, 5 and 7.
* @param remote_id optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getUWBChannel(int* channel_num, uint16_t remote_id = NULL);
/**
* configure the UWB transmission power.
*
* @note setting a large TX gain may cause the system to fall out of regulation. Applications that require regulations must set an appropriate TX gain to meet the spectral mask of your region. This can be verified with a spectrum analyzer.
*
* This function configures the UWB transmission power gain. The default value is different for each UWB channel.
* Setting a larger transmit power will result in a larger range. For increased communication range (which is two-way), both the
* transmitter and the receiver must set the appropriate transmit power.
* Changing the UWB channel will reset the power to the default value.
*
* @param txgain_dB the transmission gain in dB. Possible values are between 0dB and 33.5dB, with a resolution of 0.5dB.
* @param remote_id optional parameter that determines the remote device to be used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setTxPower(float txgain_dB, uint16_t remote_id = NULL);
/**
* Obtain the UWB transmission power.
*
* This function obtains the configured UWB transmission power gain. The default value is different for each UWB channel.
* Changing the UWB channel will reset the TX power to the default value.
*
* @param txgain_dB the configured transmission gain in dB. Possible values are between 0dB and 33.5dB, with a resolution of 0.5dB.
* @param remote_id optional parameter that determines the remote device to be used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getTxPower(float* txgain_dB, uint16_t remote_id = NULL);
/** @}*/
/** \addtogroup system_functions
* @{
*/
/**
* Obtain the who_am_i value.
* This function reads the reg:POZYX_WHO_AM_I register.
*
* @param whoami: reference to the pointer where the read data should be stored e.g. whoami
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getWhoAmI(uint8_t *whoami, uint16_t remote_id = NULL);
/**
* Obtain the firmware version.
* This function reads the reg:POZYX_FIRMWARE_VER register.
*
* @param firmware: reference to the pointer where the read data should be stored e.g. the firmware version
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getFirmwareVersion(uint8_t *firmware, uint16_t remote_id = NULL);
/**
* Obtain hte hardware version.
* This function reads the reg:POZYX_HARDWARE_VER register.
*
* @param data: reference to the pointer where the read data should be stored e.g. hardware version
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getHardwareVersion(uint8_t *hardware, uint16_t remote_id = NULL);
/**
* Obtain the selftest result.
* This function reads the reg:POZYX_ST_RESULT register.
*
* @param data: reference to the pointer where the read data should be stored e.g. the selftest result
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getSelftest(uint8_t *selftest, uint16_t remote_id = NULL);
/**
* Obtain the error code.
* This function reads the reg:POZYX_ERRORCODE register.
*
* @param data: reference to the pointer where the read data should be stored e.g. the error code
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getErrorCode(uint8_t *error_code, uint16_t remote_id = NULL);
/**
* Obtain the interrupt status.
* This function reads the reg:POZYX_INT_STATUS register.
*
* @param data: reference to the pointer where the read data should be stored e.g. the interrupt status
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*
* @see waitForFlag
*/
static int getInterruptStatus(uint8_t *interrupts, uint16_t remote_id = NULL);
/**
* Obtain the calibration status.
* This function reads the reg:POZYX_CALIB_STATUS register.
*
* @param data: reference to the pointer where the read data should be stored e.g. calibration status
* @param remote_id: optional parameter that determines the remote device to be read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getCalibrationStatus(uint8_t *calibration_status, uint16_t remote_id = NULL);
/**
* Obtain the digital value on one of the GPIO pins.
* Function to retieve the value of the given General Purpose Input/output pin (GPIO) on the target device
*
* @param gpio_num: the gpio pin to be set or retrieved. Possible values are 1, 2, 3 or 4.
* @param value: the pointer that stores the value for the GPIO.
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*
* @note In firmware version v0.9. The GPIO state cannot be read remotely.
*/
static int getGPIO(int gpio_num, uint8_t *value, uint16_t remote_id = NULL);
/**
* Set the digital value on one of the GPIO pins.
* Function to set or set the value of the given GPIO on the target device
*
* @param gpio_num: the gpio pin to be set or retrieved. Possible values are 1, 2, 3 or 4.
* @param value: the value for the GPIO. Can be O (LOW) or 1 (HIGH).
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setGPIO(int gpio_num, uint8_t value, uint16_t remote_id = NULL);
/**
* Trigger a software reset of the Pozyx device.
* Function that will trigger the reset of the system.
* This will reload all configurations from flash memory, or to their default values.
*
* @param remote_id: optional parameter that determines the remote device to be used.
*
* @see clearConfiguration, saveConfiguration
*/
static void resetSystem(uint16_t remote_id = NULL);
/**
* Function for turning the leds on and off.
* This function allows you to turn one of the 4 LEDs on the Pozyx board on or off.
* By default, the LEDs are controlled by the Pozyx system to give status information.
* This can be changed using the function setLedConfig.
*
* @param led_num: the led number to be controlled, value between 1, 2, 3 or 4.
* @param state: the state to set the selected led to. Can be 0 (led is off) or 1 (led is on)
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*
* @see setLedConfig
*/
static int setLed(int led_num, boolean state, uint16_t remote_id = NULL);
/**
* Function to obtain the interrupt configuration.
* This functions obtains the interrupt mask from the register reg:POZYX_INT_MASK.
* The interrupt mask is used to determine which event trigger an interrupt.
*
* @param mask: the configured interrupt mask
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getInterruptMask(uint8_t *mask, uint16_t remote_id = NULL);
/**
* Function to configure the interrupts.
* Function to configure the interrupts by means of the interrupt mask from the register reg:POZYX_INT_MASK.
* The interrupt mask is used to determine which event trigger an interrupt.
*
* @param mask: reference to the interrupt mask to be written. Bit-wise combinations of the following flags are allowed: #POZYX_INT_MASK_ERR,
* #POZYX_INT_MASK_POS, #POZYX_INT_MASK_IMU, #POZYX_INT_MASK_RX_DATA, #POZYX_INT_MASK_FUNC.
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setInterruptMask(uint8_t mask, uint16_t remote_id = NULL);
/**
* Obtain the pull configuration of a GPIO pin.
* Function to obtain the configured pin mode of the GPIO for the given pin number. This is performed by reading from
* the reg:POZYX_CONFIG_GPIO1 up to reg:POZYX_CONFIG_GPIO4 register.
*
* @param gpio_num: the pin to update
* @param mode: pointer to the mode of GPIO. Possible values #POZYX_GPIO_DIGITAL_INPUT, #POZYX_GPIO_PUSHPULL, #POZYX_GPIO_OPENDRAIN
* @param remote_id: optional parameter that determines the remote device to be used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getConfigModeGPIO(int gpio_num, uint8_t *mode, uint16_t remote_id = NULL);
/**
* Obtain the pull configuration of a GPIO pin.
* Function to obtain the configured pull resistor of the GPIO for the given pin number. This is performed by reading from
* the reg:POZYX_CONFIG_GPIO1 up to reg:POZYX_CONFIG_GPIO4 register.
*
* @param gpio_num: the pin to update
* @param pull: pull configuration of GPIO. Possible values are #POZYX_GPIO_NOPULL, #POZYX_GPIO_PULLUP, #POZYX_GPIO_PULLDOWN.
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int getConfigPullGPIO(int gpio_num, uint8_t *pull, uint16_t remote_id = NULL);
/**
* Configure the GPIOs.
* Function to set the configuration mode of the GPIO for the given pin number. This is performed by writing to
* the reg:POZYX_CONFIG_GPIO1 up to reg:POZYX_CONFIG_GPIO4 register.
*
* @param gpio_num: the GPIO pin to update. Possible values are 1, 2, 3 or 4.
* @param mode: the mode of GPIO. Possible values #POZYX_GPIO_DIGITAL_INPUT, #POZYX_GPIO_PUSHPULL, #POZYX_GPIO_OPENDRAIN
* @param pull: pull configuration of GPIO. Possible values are #POZYX_GPIO_NOPULL, #POZYX_GPIO_PULLUP, #POZYX_GPIO_PULLDOWN.
* @param remote_id: optional parameter that determines the remote device to be used
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*/
static int setConfigGPIO(int gpio_num, int mode, int pull, uint16_t remote_id = NULL);
/**
* Configure the LEDs.
* This function configures the 6 LEDs on the pozyx device by writing to the register reg:POZYX_LED_CTRL.
* More specifically, the function configures which LEDs give system information. By default all the LEDs
* will give system information.
*
* @param config default: the configuration to be set. See POZYX_LED_CTRL for details.
* @param remote_id: optional parameter that determines the remote device to be used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAILURE function failed.
* @retval #POZYX_TIMEOUT function timed out, no response received.
*
* @see setLed
*/
static int setLedConfig(uint8_t config = 0x0, uint16_t remote_id = NULL);
/**
* Configure the interrupt pin.
*
* @param pin pin id on the pozyx device, can be 1,2,3,4 (or 5 or 6 on the pozyx tag)
* @param mode push-pull or pull-mode
* @param bActiveHigh is the interrupt active level HIGH (i.e. 3.3V)
* @param bLatch should the interrupt be a short pulse or should it latch until the interrupt status register is read
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAIL function failed.
*/
static int configInterruptPin(int pin, int mode, int bActiveHigh, int bLatch, uint16_t remote_id=NULL);
/**
* Save (part of) the configuration to Flash memory.
* @version Requires firmware version v1.0
*
* This functions stores (parts of) the configurable Pozyx settings in the non-volatile flash memory of the Pozyx device.
* This function will save the current settings and on the next startup of the Pozyx device these saved settings will be loaded automatically.
* settings from the flash memory. All registers that are writable, the anchor ids for positioning and the device list (which contains the anchor coordinates) can be saved.
*
* @param type this specifies what should be saved. Possible options are #POZYX_FLASH_REGS, #POZYX_FLASH_ANCHOR_IDS or #POZYX_FLASH_NETWORK.
* @param registers an option array that holds all the register addresses for which the value must be saved. All registers that are writable are allowed.
* @param num_registers optional parameter that determines the length of the registers array.
* @param remote_id optional parameter that determines the remote device to be used.
*
* @retval #POZYX_SUCCESS success.
* @retval #POZYX_FAIL function failed.
* @retval #POZYX_TIMEOUT function timed out.
*
* @see clearConfiguration
*/
static int saveConfiguration(int type, uint8_t registers[] = NULL, int num_registers = 0, uint16_t remote_id = NULL);
/**
* Save registers to the flash memory. See saveConfiguration for more information
* @version Requires firmware version v1.0
*
* @param registers an option array that holds all the register addresses for which the value must be saved. All registers that are writable are allowed.
* @param num_registers optional parameter that determines the length of the registers array.
* @param remote_id optional parameter that determines the remote device to be used.