amiro-lld / drivers / DW1000 / v1 / alld_DW1000.c @ 23ab29c0
History | View | Annotate | Download (151 KB)
1 |
/*
|
---|---|
2 |
AMiRo-LLD is a compilation of low-level hardware drivers for the Autonomous Mini Robot (AMiRo) platform.
|
3 |
Copyright (C) 2016..2019 Thomas Schöpping et al.
|
4 |
|
5 |
This program is free software: you can redistribute it and/or modify
|
6 |
it under the terms of the GNU Lesser General Public License as published by
|
7 |
the Free Software Foundation, either version 3 of the License, or
|
8 |
(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 Lesser General Public License for more details.
|
14 |
|
15 |
You should have received a copy of the GNU Lesser General Public License
|
16 |
along with this program. If not, see <http://www.gnu.org/licenses/>.
|
17 |
*/
|
18 |
|
19 |
/*! ------------------------------------------------------------------------------------------------------------------
|
20 |
* @file deca_device.c
|
21 |
* @brief Decawave device configuration and control functions
|
22 |
*
|
23 |
* @attention
|
24 |
*
|
25 |
* Copyright 2013 (c) Decawave Ltd, Dublin, Ireland.
|
26 |
*
|
27 |
* All rights reserved.
|
28 |
*
|
29 |
*/
|
30 |
|
31 |
#include <alld_DW1000.h> |
32 |
#include <alld_DW1000_regs.h> |
33 |
#include <assert.h> |
34 |
#include <string.h> |
35 |
#include <stdlib.h> |
36 |
#include <math.h> |
37 |
|
38 |
|
39 |
// HW dependent implementation (see bottom of file)
|
40 |
static int writetospi(uint16_t headerLength, |
41 |
const uint8_t *headerBuffer,
|
42 |
uint32_t bodyLength, |
43 |
const uint8_t *bodyBuffer);
|
44 |
|
45 |
static int readfromspi(uint16_t headerLength, |
46 |
const uint8_t *headerBuffer,
|
47 |
uint32_t readlength, |
48 |
uint8_t *readBuffer); |
49 |
|
50 |
|
51 |
// Defines for enable_clocks function
|
52 |
#define FORCE_SYS_XTI 0 |
53 |
#define ENABLE_ALL_SEQ 1 |
54 |
#define FORCE_SYS_PLL 2 |
55 |
#define READ_ACC_ON 7 |
56 |
#define READ_ACC_OFF 8 |
57 |
#define FORCE_OTP_ON 11 |
58 |
#define FORCE_OTP_OFF 12 |
59 |
#define FORCE_TX_PLL 13 |
60 |
#define FORCE_LDE 14 |
61 |
|
62 |
// Defines for ACK request bitmask in DATA and MAC COMMAND frame control (first byte) - Used to detect AAT bit wrongly set.
|
63 |
#define FCTRL_ACK_REQ_MASK 0x20 |
64 |
// Frame control maximum length in bytes.
|
65 |
#define FCTRL_LEN_MAX 2 |
66 |
|
67 |
|
68 |
typedef struct { |
69 |
uint32_t lo32; |
70 |
uint16_t target[NUM_PRF]; |
71 |
} agc_cfg_struct ; |
72 |
|
73 |
extern const agc_cfg_struct agc_config ; |
74 |
|
75 |
//SFD threshold settings for 110k, 850k, 6.8Mb standard and non-standard
|
76 |
extern const uint16_t sftsh[NUM_BR][NUM_SFD]; |
77 |
|
78 |
extern const uint16_t dtune1[NUM_PRF]; |
79 |
|
80 |
#define XMLPARAMS_VERSION (1.17f) |
81 |
|
82 |
extern const uint32_t fs_pll_cfg[NUM_CH]; |
83 |
extern const uint8_t fs_pll_tune[NUM_CH]; |
84 |
extern const uint8_t rx_config[NUM_BW]; |
85 |
extern const uint32_t tx_config[NUM_CH]; |
86 |
extern const uint8_t dwnsSFDlen[NUM_BR]; //length of SFD for each of the bitrates |
87 |
extern const uint32_t digital_bb_config[NUM_PRF][NUM_PACS]; |
88 |
//extern const uint8_t chan_idx[NUM_CH_SUPPORTED]; // move to header file
|
89 |
extern const double txpwr_compensation[NUM_CH]; |
90 |
|
91 |
#define PEAK_MULTPLIER (0x60) //3 -> (0x3 * 32) & 0x00E0 |
92 |
#define N_STD_FACTOR (13) |
93 |
#define LDE_PARAM1 (PEAK_MULTPLIER | N_STD_FACTOR)
|
94 |
|
95 |
#define LDE_PARAM3_16 (0x1607) |
96 |
#define LDE_PARAM3_64 (0x0607) |
97 |
|
98 |
#define MIXER_GAIN_STEP (0.5) |
99 |
#define DA_ATTN_STEP (2.5) |
100 |
|
101 |
// #define DWT_API_ERROR_CHECK // define so API checks config input parameters
|
102 |
|
103 |
//-----------------------------------------
|
104 |
// map the channel number to the index in the configuration arrays below
|
105 |
// 0th element is chan 1, 1st is chan 2, 2nd is chan 3, 3rd is chan 4, 4th is chan 5, 5th is chan 7
|
106 |
const uint8_t chan_idx[NUM_CH_SUPPORTED] = {0, 0, 1, 2, 3, 4, 0, 5}; |
107 |
|
108 |
//-----------------------------------------
|
109 |
const uint32_t tx_config[NUM_CH] =
|
110 |
{ |
111 |
RF_TXCTRL_CH1, |
112 |
RF_TXCTRL_CH2, |
113 |
RF_TXCTRL_CH3, |
114 |
RF_TXCTRL_CH4, |
115 |
RF_TXCTRL_CH5, |
116 |
RF_TXCTRL_CH7, |
117 |
}; |
118 |
|
119 |
//Frequency Synthesiser - PLL configuration
|
120 |
const uint32_t fs_pll_cfg[NUM_CH] =
|
121 |
{ |
122 |
FS_PLLCFG_CH1, |
123 |
FS_PLLCFG_CH2, |
124 |
FS_PLLCFG_CH3, |
125 |
FS_PLLCFG_CH4, |
126 |
FS_PLLCFG_CH5, |
127 |
FS_PLLCFG_CH7 |
128 |
}; |
129 |
|
130 |
//Frequency Synthesiser - PLL tuning
|
131 |
const uint8_t fs_pll_tune[NUM_CH] =
|
132 |
{ |
133 |
FS_PLLTUNE_CH1, |
134 |
FS_PLLTUNE_CH2, |
135 |
FS_PLLTUNE_CH3, |
136 |
FS_PLLTUNE_CH4, |
137 |
FS_PLLTUNE_CH5, |
138 |
FS_PLLTUNE_CH7 |
139 |
}; |
140 |
|
141 |
//bandwidth configuration
|
142 |
const uint8_t rx_config[NUM_BW] =
|
143 |
{ |
144 |
RF_RXCTRLH_NBW, |
145 |
RF_RXCTRLH_WBW |
146 |
}; |
147 |
|
148 |
|
149 |
const agc_cfg_struct agc_config =
|
150 |
{ |
151 |
AGC_TUNE2_VAL, |
152 |
{ AGC_TUNE1_16M , AGC_TUNE1_64M } //adc target
|
153 |
}; |
154 |
|
155 |
//DW non-standard SFD length for 110k, 850k and 6.81M
|
156 |
const uint8_t dwnsSFDlen[NUM_BR] =
|
157 |
{ |
158 |
DW_NS_SFD_LEN_110K, |
159 |
DW_NS_SFD_LEN_850K, |
160 |
DW_NS_SFD_LEN_6M8 |
161 |
}; |
162 |
|
163 |
// SFD Threshold
|
164 |
const uint16_t sftsh[NUM_BR][NUM_SFD] =
|
165 |
{ |
166 |
{ |
167 |
DRX_TUNE0b_110K_STD, |
168 |
DRX_TUNE0b_110K_NSTD |
169 |
}, |
170 |
{ |
171 |
DRX_TUNE0b_850K_STD, |
172 |
DRX_TUNE0b_850K_NSTD |
173 |
}, |
174 |
{ |
175 |
DRX_TUNE0b_6M8_STD, |
176 |
DRX_TUNE0b_6M8_NSTD |
177 |
} |
178 |
}; |
179 |
|
180 |
const uint16_t dtune1[NUM_PRF] =
|
181 |
{ |
182 |
DRX_TUNE1a_PRF16, |
183 |
DRX_TUNE1a_PRF64 |
184 |
}; |
185 |
|
186 |
const uint32_t digital_bb_config[NUM_PRF][NUM_PACS] =
|
187 |
{ |
188 |
{ |
189 |
DRX_TUNE2_PRF16_PAC8, |
190 |
DRX_TUNE2_PRF16_PAC16, |
191 |
DRX_TUNE2_PRF16_PAC32, |
192 |
DRX_TUNE2_PRF16_PAC64 |
193 |
}, |
194 |
{ |
195 |
DRX_TUNE2_PRF64_PAC8, |
196 |
DRX_TUNE2_PRF64_PAC16, |
197 |
DRX_TUNE2_PRF64_PAC32, |
198 |
DRX_TUNE2_PRF64_PAC64 |
199 |
} |
200 |
}; |
201 |
|
202 |
const uint16_t lde_replicaCoeff[PCODES] =
|
203 |
{ |
204 |
0, // No preamble code 0 |
205 |
LDE_REPC_PCODE_1, |
206 |
LDE_REPC_PCODE_2, |
207 |
LDE_REPC_PCODE_3, |
208 |
LDE_REPC_PCODE_4, |
209 |
LDE_REPC_PCODE_5, |
210 |
LDE_REPC_PCODE_6, |
211 |
LDE_REPC_PCODE_7, |
212 |
LDE_REPC_PCODE_8, |
213 |
LDE_REPC_PCODE_9, |
214 |
LDE_REPC_PCODE_10, |
215 |
LDE_REPC_PCODE_11, |
216 |
LDE_REPC_PCODE_12, |
217 |
LDE_REPC_PCODE_13, |
218 |
LDE_REPC_PCODE_14, |
219 |
LDE_REPC_PCODE_15, |
220 |
LDE_REPC_PCODE_16, |
221 |
LDE_REPC_PCODE_17, |
222 |
LDE_REPC_PCODE_18, |
223 |
LDE_REPC_PCODE_19, |
224 |
LDE_REPC_PCODE_20, |
225 |
LDE_REPC_PCODE_21, |
226 |
LDE_REPC_PCODE_22, |
227 |
LDE_REPC_PCODE_23, |
228 |
LDE_REPC_PCODE_24 |
229 |
}; |
230 |
|
231 |
const double txpwr_compensation[NUM_CH] = { |
232 |
0.0, |
233 |
0.035, |
234 |
0.0, |
235 |
0.0, |
236 |
0.065, |
237 |
0.0 |
238 |
}; |
239 |
|
240 |
|
241 |
const uint8_t chan_idxnb[NUM_CH_SUPPORTED] = {0, 0, 1, 2, 0, 3, 0, 0}; //only channels 1,2,3 and 5 are in the narrow band tables |
242 |
const uint8_t chan_idxwb[NUM_CH_SUPPORTED] = {0, 0, 0, 0, 0, 0, 0, 1}; //only channels 4 and 7 are in in the wide band tables |
243 |
|
244 |
//---------------------------------------------------------------------------------------------------------------------------
|
245 |
// Range Bias Correction TABLES of range values in integer units of 25 CM, for 8-bit unsigned storage, MUST END IN 255 !!!!!!
|
246 |
//---------------------------------------------------------------------------------------------------------------------------
|
247 |
|
248 |
// offsets to nearest centimeter for index 0, all rest are +1 cm per value
|
249 |
|
250 |
#define CM_OFFSET_16M_NB (-23) // for normal band channels at 16 MHz PRF |
251 |
#define CM_OFFSET_16M_WB (-28) // for wider band channels at 16 MHz PRF |
252 |
#define CM_OFFSET_64M_NB (-17) // for normal band channels at 64 MHz PRF |
253 |
#define CM_OFFSET_64M_WB (-30) // for wider band channels at 64 MHz PRF |
254 |
|
255 |
|
256 |
//---------------------------------------------------------------------------------------------------------------------------
|
257 |
// range25cm16PRFnb: Range Bias Correction table for narrow band channels at 16 MHz PRF, NB: !!!! each MUST END IN 255 !!!!
|
258 |
//---------------------------------------------------------------------------------------------------------------------------
|
259 |
|
260 |
const uint8_t range25cm16PRFnb[4][NUM_16M_OFFSET] = |
261 |
{ |
262 |
// ch 1 - range25cm16PRFnb
|
263 |
{ |
264 |
1,
|
265 |
3,
|
266 |
4,
|
267 |
5,
|
268 |
7,
|
269 |
9,
|
270 |
11,
|
271 |
12,
|
272 |
13,
|
273 |
15,
|
274 |
18,
|
275 |
20,
|
276 |
23,
|
277 |
25,
|
278 |
28,
|
279 |
30,
|
280 |
33,
|
281 |
36,
|
282 |
40,
|
283 |
43,
|
284 |
47,
|
285 |
50,
|
286 |
54,
|
287 |
58,
|
288 |
63,
|
289 |
66,
|
290 |
71,
|
291 |
76,
|
292 |
82,
|
293 |
89,
|
294 |
98,
|
295 |
109,
|
296 |
127,
|
297 |
155,
|
298 |
222,
|
299 |
255,
|
300 |
255
|
301 |
}, |
302 |
|
303 |
// ch 2 - range25cm16PRFnb
|
304 |
{ |
305 |
1,
|
306 |
2,
|
307 |
4,
|
308 |
5,
|
309 |
6,
|
310 |
8,
|
311 |
9,
|
312 |
10,
|
313 |
12,
|
314 |
13,
|
315 |
15,
|
316 |
18,
|
317 |
20,
|
318 |
22,
|
319 |
24,
|
320 |
27,
|
321 |
29,
|
322 |
32,
|
323 |
35,
|
324 |
38,
|
325 |
41,
|
326 |
44,
|
327 |
47,
|
328 |
51,
|
329 |
55,
|
330 |
58,
|
331 |
62,
|
332 |
66,
|
333 |
71,
|
334 |
78,
|
335 |
85,
|
336 |
96,
|
337 |
111,
|
338 |
135,
|
339 |
194,
|
340 |
240,
|
341 |
255
|
342 |
}, |
343 |
|
344 |
// ch 3 - range25cm16PRFnb
|
345 |
{ |
346 |
1,
|
347 |
2,
|
348 |
3,
|
349 |
4,
|
350 |
5,
|
351 |
7,
|
352 |
8,
|
353 |
9,
|
354 |
10,
|
355 |
12,
|
356 |
14,
|
357 |
16,
|
358 |
18,
|
359 |
20,
|
360 |
22,
|
361 |
24,
|
362 |
26,
|
363 |
28,
|
364 |
31,
|
365 |
33,
|
366 |
36,
|
367 |
39,
|
368 |
42,
|
369 |
45,
|
370 |
49,
|
371 |
52,
|
372 |
55,
|
373 |
59,
|
374 |
63,
|
375 |
69,
|
376 |
76,
|
377 |
85,
|
378 |
98,
|
379 |
120,
|
380 |
173,
|
381 |
213,
|
382 |
255
|
383 |
}, |
384 |
|
385 |
// ch 5 - range25cm16PRFnb
|
386 |
{ |
387 |
1,
|
388 |
1,
|
389 |
2,
|
390 |
3,
|
391 |
4,
|
392 |
5,
|
393 |
6,
|
394 |
6,
|
395 |
7,
|
396 |
8,
|
397 |
9,
|
398 |
11,
|
399 |
12,
|
400 |
14,
|
401 |
15,
|
402 |
16,
|
403 |
18,
|
404 |
20,
|
405 |
21,
|
406 |
23,
|
407 |
25,
|
408 |
27,
|
409 |
29,
|
410 |
31,
|
411 |
34,
|
412 |
36,
|
413 |
38,
|
414 |
41,
|
415 |
44,
|
416 |
48,
|
417 |
53,
|
418 |
59,
|
419 |
68,
|
420 |
83,
|
421 |
120,
|
422 |
148,
|
423 |
255
|
424 |
} |
425 |
}; // end range25cm16PRFnb
|
426 |
|
427 |
|
428 |
//---------------------------------------------------------------------------------------------------------------------------
|
429 |
// range25cm16PRFwb: Range Bias Correction table for wide band channels at 16 MHz PRF, NB: !!!! each MUST END IN 255 !!!!
|
430 |
//---------------------------------------------------------------------------------------------------------------------------
|
431 |
|
432 |
const uint8_t range25cm16PRFwb[2][NUM_16M_OFFSETWB] = |
433 |
{ |
434 |
// ch 4 - range25cm16PRFwb
|
435 |
{ |
436 |
7,
|
437 |
7,
|
438 |
8,
|
439 |
9,
|
440 |
9,
|
441 |
10,
|
442 |
11,
|
443 |
11,
|
444 |
12,
|
445 |
13,
|
446 |
14,
|
447 |
15,
|
448 |
16,
|
449 |
17,
|
450 |
18,
|
451 |
19,
|
452 |
20,
|
453 |
21,
|
454 |
22,
|
455 |
23,
|
456 |
24,
|
457 |
26,
|
458 |
27,
|
459 |
28,
|
460 |
30,
|
461 |
31,
|
462 |
32,
|
463 |
34,
|
464 |
36,
|
465 |
38,
|
466 |
40,
|
467 |
42,
|
468 |
44,
|
469 |
46,
|
470 |
48,
|
471 |
50,
|
472 |
52,
|
473 |
55,
|
474 |
57,
|
475 |
59,
|
476 |
61,
|
477 |
63,
|
478 |
66,
|
479 |
68,
|
480 |
71,
|
481 |
74,
|
482 |
78,
|
483 |
81,
|
484 |
85,
|
485 |
89,
|
486 |
94,
|
487 |
99,
|
488 |
104,
|
489 |
110,
|
490 |
116,
|
491 |
123,
|
492 |
130,
|
493 |
139,
|
494 |
150,
|
495 |
164,
|
496 |
182,
|
497 |
207,
|
498 |
238,
|
499 |
255,
|
500 |
255,
|
501 |
255,
|
502 |
255,
|
503 |
255
|
504 |
}, |
505 |
|
506 |
// ch 7 - range25cm16PRFwb
|
507 |
{ |
508 |
4,
|
509 |
5,
|
510 |
5,
|
511 |
5,
|
512 |
6,
|
513 |
6,
|
514 |
7,
|
515 |
7,
|
516 |
7,
|
517 |
8,
|
518 |
9,
|
519 |
9,
|
520 |
10,
|
521 |
10,
|
522 |
11,
|
523 |
11,
|
524 |
12,
|
525 |
13,
|
526 |
13,
|
527 |
14,
|
528 |
15,
|
529 |
16,
|
530 |
17,
|
531 |
17,
|
532 |
18,
|
533 |
19,
|
534 |
20,
|
535 |
21,
|
536 |
22,
|
537 |
23,
|
538 |
25,
|
539 |
26,
|
540 |
27,
|
541 |
29,
|
542 |
30,
|
543 |
31,
|
544 |
32,
|
545 |
34,
|
546 |
35,
|
547 |
36,
|
548 |
38,
|
549 |
39,
|
550 |
40,
|
551 |
42,
|
552 |
44,
|
553 |
46,
|
554 |
48,
|
555 |
50,
|
556 |
52,
|
557 |
55,
|
558 |
58,
|
559 |
61,
|
560 |
64,
|
561 |
68,
|
562 |
72,
|
563 |
75,
|
564 |
80,
|
565 |
85,
|
566 |
92,
|
567 |
101,
|
568 |
112,
|
569 |
127,
|
570 |
147,
|
571 |
168,
|
572 |
182,
|
573 |
194,
|
574 |
205,
|
575 |
255
|
576 |
} |
577 |
}; // end range25cm16PRFwb
|
578 |
|
579 |
//---------------------------------------------------------------------------------------------------------------------------
|
580 |
// range25cm64PRFnb: Range Bias Correction table for narrow band channels at 64 MHz PRF, NB: !!!! each MUST END IN 255 !!!!
|
581 |
//---------------------------------------------------------------------------------------------------------------------------
|
582 |
|
583 |
const uint8_t range25cm64PRFnb[4][NUM_64M_OFFSET] = |
584 |
{ |
585 |
// ch 1 - range25cm64PRFnb
|
586 |
{ |
587 |
1,
|
588 |
2,
|
589 |
2,
|
590 |
3,
|
591 |
4,
|
592 |
5,
|
593 |
7,
|
594 |
10,
|
595 |
13,
|
596 |
16,
|
597 |
19,
|
598 |
22,
|
599 |
24,
|
600 |
27,
|
601 |
30,
|
602 |
32,
|
603 |
35,
|
604 |
38,
|
605 |
43,
|
606 |
48,
|
607 |
56,
|
608 |
78,
|
609 |
101,
|
610 |
120,
|
611 |
157,
|
612 |
255
|
613 |
}, |
614 |
|
615 |
// ch 2 - range25cm64PRFnb
|
616 |
{ |
617 |
1,
|
618 |
2,
|
619 |
2,
|
620 |
3,
|
621 |
4,
|
622 |
4,
|
623 |
6,
|
624 |
9,
|
625 |
12,
|
626 |
14,
|
627 |
17,
|
628 |
19,
|
629 |
21,
|
630 |
24,
|
631 |
26,
|
632 |
28,
|
633 |
31,
|
634 |
33,
|
635 |
37,
|
636 |
42,
|
637 |
49,
|
638 |
68,
|
639 |
89,
|
640 |
105,
|
641 |
138,
|
642 |
255
|
643 |
}, |
644 |
|
645 |
// ch 3 - range25cm64PRFnb
|
646 |
{ |
647 |
1,
|
648 |
1,
|
649 |
2,
|
650 |
3,
|
651 |
3,
|
652 |
4,
|
653 |
5,
|
654 |
8,
|
655 |
10,
|
656 |
13,
|
657 |
15,
|
658 |
17,
|
659 |
19,
|
660 |
21,
|
661 |
23,
|
662 |
25,
|
663 |
27,
|
664 |
30,
|
665 |
33,
|
666 |
37,
|
667 |
44,
|
668 |
60,
|
669 |
79,
|
670 |
93,
|
671 |
122,
|
672 |
255
|
673 |
}, |
674 |
|
675 |
// ch 5 - range25cm64PRFnb
|
676 |
{ |
677 |
1,
|
678 |
1,
|
679 |
1,
|
680 |
2,
|
681 |
2,
|
682 |
3,
|
683 |
4,
|
684 |
6,
|
685 |
7,
|
686 |
9,
|
687 |
10,
|
688 |
12,
|
689 |
13,
|
690 |
15,
|
691 |
16,
|
692 |
17,
|
693 |
19,
|
694 |
21,
|
695 |
23,
|
696 |
26,
|
697 |
30,
|
698 |
42,
|
699 |
55,
|
700 |
65,
|
701 |
85,
|
702 |
255
|
703 |
} |
704 |
}; // end range25cm64PRFnb
|
705 |
|
706 |
//---------------------------------------------------------------------------------------------------------------------------
|
707 |
// range25cm64PRFwb: Range Bias Correction table for wide band channels at 64 MHz PRF, NB: !!!! each MUST END IN 255 !!!!
|
708 |
//---------------------------------------------------------------------------------------------------------------------------
|
709 |
|
710 |
const uint8_t range25cm64PRFwb[2][NUM_64M_OFFSETWB] = |
711 |
{ |
712 |
// ch 4 - range25cm64PRFwb
|
713 |
{ |
714 |
7,
|
715 |
8,
|
716 |
8,
|
717 |
9,
|
718 |
9,
|
719 |
10,
|
720 |
11,
|
721 |
12,
|
722 |
13,
|
723 |
13,
|
724 |
14,
|
725 |
15,
|
726 |
16,
|
727 |
16,
|
728 |
17,
|
729 |
18,
|
730 |
19,
|
731 |
19,
|
732 |
20,
|
733 |
21,
|
734 |
22,
|
735 |
24,
|
736 |
25,
|
737 |
27,
|
738 |
28,
|
739 |
29,
|
740 |
30,
|
741 |
32,
|
742 |
33,
|
743 |
34,
|
744 |
35,
|
745 |
37,
|
746 |
39,
|
747 |
41,
|
748 |
43,
|
749 |
45,
|
750 |
48,
|
751 |
50,
|
752 |
53,
|
753 |
56,
|
754 |
60,
|
755 |
64,
|
756 |
68,
|
757 |
74,
|
758 |
81,
|
759 |
89,
|
760 |
98,
|
761 |
109,
|
762 |
122,
|
763 |
136,
|
764 |
146,
|
765 |
154,
|
766 |
162,
|
767 |
178,
|
768 |
220,
|
769 |
249,
|
770 |
255,
|
771 |
255,
|
772 |
255
|
773 |
}, |
774 |
|
775 |
// ch 7 - range25cm64PRFwb
|
776 |
{ |
777 |
4,
|
778 |
5,
|
779 |
5,
|
780 |
5,
|
781 |
6,
|
782 |
6,
|
783 |
7,
|
784 |
7,
|
785 |
8,
|
786 |
8,
|
787 |
9,
|
788 |
9,
|
789 |
10,
|
790 |
10,
|
791 |
10,
|
792 |
11,
|
793 |
11,
|
794 |
12,
|
795 |
13,
|
796 |
13,
|
797 |
14,
|
798 |
15,
|
799 |
16,
|
800 |
16,
|
801 |
17,
|
802 |
18,
|
803 |
19,
|
804 |
19,
|
805 |
20,
|
806 |
21,
|
807 |
22,
|
808 |
23,
|
809 |
24,
|
810 |
25,
|
811 |
26,
|
812 |
28,
|
813 |
29,
|
814 |
31,
|
815 |
33,
|
816 |
35,
|
817 |
37,
|
818 |
39,
|
819 |
42,
|
820 |
46,
|
821 |
50,
|
822 |
54,
|
823 |
60,
|
824 |
67,
|
825 |
75,
|
826 |
83,
|
827 |
90,
|
828 |
95,
|
829 |
100,
|
830 |
110,
|
831 |
135,
|
832 |
153,
|
833 |
172,
|
834 |
192,
|
835 |
255
|
836 |
} |
837 |
}; // end range25cm64PRFwb
|
838 |
|
839 |
|
840 |
/*! ------------------------------------------------------------------------------------------------------------------
|
841 |
* Function: dwt_getrangebias()
|
842 |
*
|
843 |
* Description: This function is used to return the range bias correction need for TWR with DW1000 units.
|
844 |
*
|
845 |
* input parameters:
|
846 |
* @param chan - specifies the operating channel (e.g. 1, 2, 3, 4, 5, 6 or 7)
|
847 |
* @param range - the calculated distance before correction
|
848 |
* @param prf - this is the PRF e.g. DWT_PRF_16M or DWT_PRF_64M
|
849 |
*
|
850 |
* output parameters
|
851 |
*
|
852 |
* returns correction needed in meters
|
853 |
*/
|
854 |
double dwt_getrangebias(uint8_t chan, float range, uint8_t prf) |
855 |
{ |
856 |
//first get the lookup index that corresponds to given range for a particular channel at 16M PRF
|
857 |
int i = 0 ; |
858 |
int chanIdx ;
|
859 |
int cmoffseti ; // integer number of CM offset |
860 |
|
861 |
double mOffset ; // final offset result in metres |
862 |
|
863 |
// NB: note we may get some small negitive values e.g. up to -50 cm.
|
864 |
|
865 |
int rangeint25cm = (int) ((double)range * 4.00) ; // convert range to integer number of 25cm values. |
866 |
|
867 |
if (rangeint25cm > 255) rangeint25cm = 255 ; // make sure it matches largest value in table (all tables end in 255 !!!!) |
868 |
|
869 |
if (prf == DWT_PRF_16M)
|
870 |
{ |
871 |
switch(chan)
|
872 |
{ |
873 |
case 4: |
874 |
case 7: |
875 |
{ |
876 |
chanIdx = chan_idxwb[chan]; |
877 |
while (rangeint25cm > range25cm16PRFwb[chanIdx][i]) i++ ; // find index in table corresponding to range |
878 |
cmoffseti = i + CM_OFFSET_16M_WB ; // nearest centimeter correction
|
879 |
} |
880 |
break;
|
881 |
default:
|
882 |
{ |
883 |
chanIdx = chan_idxnb[chan]; |
884 |
while (rangeint25cm > range25cm16PRFnb[chanIdx][i]) i++ ; // find index in table corresponding to range |
885 |
cmoffseti = i + CM_OFFSET_16M_NB ; // nearest centimeter correction
|
886 |
} |
887 |
}//end of switch
|
888 |
} |
889 |
else // 64M PRF |
890 |
{ |
891 |
switch(chan)
|
892 |
{ |
893 |
case 4: |
894 |
case 7: |
895 |
{ |
896 |
chanIdx = chan_idxwb[chan]; |
897 |
while (rangeint25cm > range25cm64PRFwb[chanIdx][i]) i++ ; // find index in table corresponding to range |
898 |
cmoffseti = i + CM_OFFSET_64M_WB ; // nearest centimeter correction
|
899 |
} |
900 |
break;
|
901 |
default:
|
902 |
{ |
903 |
chanIdx = chan_idxnb[chan]; |
904 |
while (rangeint25cm > range25cm64PRFnb[chanIdx][i]) i++ ; // find index in table corresponding to range |
905 |
cmoffseti = i + CM_OFFSET_64M_NB ; // nearest centimeter correction
|
906 |
} |
907 |
}//end of switch
|
908 |
} // end else
|
909 |
|
910 |
|
911 |
mOffset = (double) cmoffseti ; // offset result in centimmetres |
912 |
|
913 |
mOffset *= 0.01 ; // convert to metres |
914 |
|
915 |
return (mOffset) ;
|
916 |
} |
917 |
|
918 |
// -------------------------------------------------------------------------------------------------------------------
|
919 |
//
|
920 |
// Internal functions for controlling and configuring the device
|
921 |
//
|
922 |
// -------------------------------------------------------------------------------------------------------------------
|
923 |
|
924 |
// Enable and Configure specified clocks
|
925 |
void _dwt_enableclocks(int clocks) ; |
926 |
// Configure the ucode (FP algorithm) parameters
|
927 |
void _dwt_configlde(int prf); |
928 |
// Load ucode from OTP/ROM
|
929 |
void _dwt_loaducodefromrom(void); |
930 |
// Read non-volatile memory
|
931 |
uint32_t _dwt_otpread(uint32_t address); |
932 |
// Program the non-volatile memory
|
933 |
int32_t _dwt_otpprogword32(uint32_t data, uint16_t address); |
934 |
// Upload the device configuration into always on memory
|
935 |
void _dwt_aonarrayupload(void); |
936 |
// -------------------------------------------------------------------------------------------------------------------
|
937 |
|
938 |
/*!
|
939 |
* Static data for DW1000 DecaWave Transceiver control
|
940 |
*/
|
941 |
|
942 |
static dwt_local_data_t dw1000local[DWT_NUM_DW_DEV] ; // Static local device data, can be an array to support multiple DW1000 testing applications/platforms |
943 |
static dwt_local_data_t *pdw1000local = dw1000local ; // Static local data structure pointer |
944 |
|
945 |
|
946 |
/*! ------------------------------------------------------------------------------------------------------------------
|
947 |
* @fn dwt_setdevicedataptr()
|
948 |
*
|
949 |
* @brief This function sets the local data structure pointer to point to the structure in the local array as given by the index.
|
950 |
*
|
951 |
* input parameters
|
952 |
* @param index - selects the array object to point to. Must be within the array bounds, i.e. < DWT_NUM_DW_DEV
|
953 |
*
|
954 |
* output parameters
|
955 |
*
|
956 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
957 |
*/
|
958 |
int dwt_setdevicedataptr(unsigned int index) |
959 |
{ |
960 |
// Check the index is within the array bounds
|
961 |
if (DWT_NUM_DW_DEV > index) // return error if index outside the array bounds |
962 |
{ |
963 |
return DWT_ERROR ;
|
964 |
} |
965 |
|
966 |
pdw1000local = &dw1000local[index]; |
967 |
|
968 |
return DWT_SUCCESS ;
|
969 |
} |
970 |
|
971 |
/*! ------------------------------------------------------------------------------------------------------------------
|
972 |
* @fn dwt_initialise()
|
973 |
*
|
974 |
* @brief This function initiates communications with the DW1000 transceiver
|
975 |
* and reads its DEV_ID register (address 0x00) to verify the IC is one supported
|
976 |
* by this software (e.g. DW1000 32-bit device ID value is 0xDECA0130). Then it
|
977 |
* does any initial once only device configurations needed for use and initialises
|
978 |
* as necessary any static data items belonging to this low-level driver.
|
979 |
*
|
980 |
* NOTES:
|
981 |
* 1.this function needs to be run before dwt_configuresleep, also the SPI frequency has to be < 3MHz
|
982 |
* 2.it also reads and applies LDO tune and crystal trim values from OTP memory
|
983 |
*
|
984 |
* input parameters
|
985 |
* @param config - specifies what configuration to load
|
986 |
* DWT_LOADUCODE 0x1 - load the LDE microcode from ROM - enabled accurate RX timestamp
|
987 |
* DWT_LOADNONE 0x0 - do not load any values from OTP memory
|
988 |
*
|
989 |
* output parameters
|
990 |
*
|
991 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
992 |
*/
|
993 |
// OTP addresses definitions
|
994 |
#define LDOTUNE_ADDRESS (0x04) |
995 |
#define PARTID_ADDRESS (0x06) |
996 |
#define LOTID_ADDRESS (0x07) |
997 |
#define VBAT_ADDRESS (0x08) |
998 |
#define VTEMP_ADDRESS (0x09) |
999 |
#define XTRIM_ADDRESS (0x1E) |
1000 |
|
1001 |
int dwt_initialise(const uint16_t config, DW1000Driver* drv) |
1002 |
{ |
1003 |
uint16_t otp_addr = 0;
|
1004 |
uint32_t ldo_tune = 0;
|
1005 |
|
1006 |
pdw1000local->dblbuffon = 0; // Double buffer mode off by default |
1007 |
pdw1000local->wait4resp = 0;
|
1008 |
pdw1000local->sleep_mode = 0;
|
1009 |
|
1010 |
pdw1000local->cbTxDone = NULL;
|
1011 |
pdw1000local->cbRxOk = NULL;
|
1012 |
pdw1000local->cbRxTo = NULL;
|
1013 |
pdw1000local->cbRxErr = NULL;
|
1014 |
|
1015 |
pdw1000local->driver = drv; |
1016 |
|
1017 |
// Read and validate device ID return -1 if not recognised
|
1018 |
if (DWT_DEVICE_ID != dwt_readdevid()) // MP IC ONLY (i.e. DW1000) FOR THIS CODE |
1019 |
{ |
1020 |
return DWT_ERROR ;
|
1021 |
} |
1022 |
|
1023 |
// Make sure the device is completely reset before starting initialisation
|
1024 |
dwt_softreset(); |
1025 |
|
1026 |
_dwt_enableclocks(FORCE_SYS_XTI); // NOTE: set system clock to XTI - this is necessary to make sure the values read by _dwt_otpread are reliable
|
1027 |
|
1028 |
// Configure the CPLL lock detect
|
1029 |
dwt_write8bitoffsetreg(EXT_SYNC_ID, EC_CTRL_OFFSET, EC_CTRL_PLLLCK); |
1030 |
|
1031 |
// Read OTP revision number
|
1032 |
otp_addr = _dwt_otpread(XTRIM_ADDRESS) & 0xffff; // Read 32 bit value, XTAL trim val is in low octet-0 (5 bits) |
1033 |
pdw1000local->otprev = (otp_addr >> 8) & 0xff; // OTP revision is next byte |
1034 |
|
1035 |
// Load LDO tune from OTP and kick it if there is a value actually programmed.
|
1036 |
ldo_tune = _dwt_otpread(LDOTUNE_ADDRESS); |
1037 |
if((ldo_tune & 0xFF) != 0) |
1038 |
{ |
1039 |
// Kick LDO tune
|
1040 |
dwt_write8bitoffsetreg(OTP_IF_ID, OTP_SF, OTP_SF_LDO_KICK); // Set load LDE kick bit
|
1041 |
pdw1000local->sleep_mode |= AON_WCFG_ONW_LLDO; // LDO tune must be kicked at wake-up
|
1042 |
} |
1043 |
|
1044 |
// Load Part and Lot ID from OTP
|
1045 |
pdw1000local->partID = _dwt_otpread(PARTID_ADDRESS); |
1046 |
pdw1000local->lotID = _dwt_otpread(LOTID_ADDRESS); |
1047 |
|
1048 |
// XTAL trim value is set in OTP for DW1000 module and EVK/TREK boards but that might not be the case in a custom design
|
1049 |
pdw1000local->init_xtrim = otp_addr & 0x1F;
|
1050 |
if (!pdw1000local->init_xtrim) // A value of 0 means that the crystal has not been trimmed |
1051 |
{ |
1052 |
pdw1000local->init_xtrim = FS_XTALT_MIDRANGE ; // Set to mid-range if no calibration value inside
|
1053 |
} |
1054 |
// Configure XTAL trim
|
1055 |
dwt_setxtaltrim(pdw1000local->init_xtrim); |
1056 |
|
1057 |
// Load leading edge detect code
|
1058 |
if(config & DWT_LOADUCODE)
|
1059 |
{ |
1060 |
_dwt_loaducodefromrom(); |
1061 |
pdw1000local->sleep_mode |= AON_WCFG_ONW_LLDE; // microcode must be loaded at wake-up
|
1062 |
} |
1063 |
else // Should disable the LDERUN enable bit in 0x36, 0x4 |
1064 |
{ |
1065 |
uint16_t rega = dwt_read16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET+1) ;
|
1066 |
rega &= 0xFDFF ; // Clear LDERUN bit |
1067 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET+1, rega) ;
|
1068 |
} |
1069 |
|
1070 |
_dwt_enableclocks(ENABLE_ALL_SEQ); // Enable clocks for sequencing
|
1071 |
|
1072 |
// The 3 bits in AON CFG1 register must be cleared to ensure proper operation of the DW1000 in DEEPSLEEP mode.
|
1073 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG1_OFFSET, 0x00);
|
1074 |
|
1075 |
// Read system register / store local copy
|
1076 |
pdw1000local->sysCFGreg = dwt_read32bitreg(SYS_CFG_ID) ; // Read sysconfig register
|
1077 |
|
1078 |
return DWT_SUCCESS ;
|
1079 |
|
1080 |
} // end dwt_initialise()
|
1081 |
|
1082 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1083 |
* @fn dwt_otprevision()
|
1084 |
*
|
1085 |
* @brief This is used to return the read OTP revision
|
1086 |
*
|
1087 |
* NOTE: dwt_initialise() must be called prior to this function so that it can return a relevant value.
|
1088 |
*
|
1089 |
* input parameters
|
1090 |
*
|
1091 |
* output parameters
|
1092 |
*
|
1093 |
* returns the read OTP revision value
|
1094 |
*/
|
1095 |
uint8_t dwt_otprevision(void)
|
1096 |
{ |
1097 |
return pdw1000local->otprev ;
|
1098 |
} |
1099 |
|
1100 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1101 |
* @fn dwt_setfinegraintxseq()
|
1102 |
*
|
1103 |
* @brief This function enables/disables the fine grain TX sequencing (enabled by default).
|
1104 |
*
|
1105 |
* input parameters
|
1106 |
* @param enable - 1 to enable fine grain TX sequencing, 0 to disable it.
|
1107 |
*
|
1108 |
* output parameters none
|
1109 |
*
|
1110 |
* no return value
|
1111 |
*/
|
1112 |
void dwt_setfinegraintxseq(int enable) |
1113 |
{ |
1114 |
if (enable)
|
1115 |
{ |
1116 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_TXFINESEQ_OFFSET, PMSC_TXFINESEQ_ENABLE); |
1117 |
} |
1118 |
else
|
1119 |
{ |
1120 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_TXFINESEQ_OFFSET, PMSC_TXFINESEQ_DISABLE); |
1121 |
} |
1122 |
} |
1123 |
|
1124 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1125 |
* @fn dwt_setlnapamode()
|
1126 |
*
|
1127 |
* @brief This is used to enable GPIO for external LNA or PA functionality - HW dependent, consult the DW1000 User Manual.
|
1128 |
* This can also be used for debug as enabling TX and RX GPIOs is quite handy to monitor DW1000's activity.
|
1129 |
*
|
1130 |
* NOTE: Enabling PA functionality requires that fine grain TX sequencing is deactivated. This can be done using
|
1131 |
* dwt_setfinegraintxseq().
|
1132 |
*
|
1133 |
* input parameters
|
1134 |
* @param lna - 1 to enable LNA functionality, 0 to disable it
|
1135 |
* @param pa - 1 to enable PA functionality, 0 to disable it
|
1136 |
*
|
1137 |
* output parameters
|
1138 |
*
|
1139 |
* no return value
|
1140 |
*/
|
1141 |
void dwt_setlnapamode(int lna, int pa) |
1142 |
{ |
1143 |
uint32_t gpio_mode = dwt_read32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET); |
1144 |
gpio_mode &= ~(GPIO_MSGP4_MASK | GPIO_MSGP5_MASK | GPIO_MSGP6_MASK); |
1145 |
if (lna)
|
1146 |
{ |
1147 |
gpio_mode |= GPIO_PIN6_EXTRXE; |
1148 |
} |
1149 |
if (pa)
|
1150 |
{ |
1151 |
gpio_mode |= (GPIO_PIN5_EXTTXE | GPIO_PIN4_EXTPA); |
1152 |
} |
1153 |
dwt_write32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET, gpio_mode); |
1154 |
} |
1155 |
|
1156 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1157 |
* @fn dwt_setgpiodirection()
|
1158 |
*
|
1159 |
* @brief This is used to set GPIO direction as an input (1) or output (0)
|
1160 |
*
|
1161 |
* input parameters
|
1162 |
* @param gpioNum - this is the GPIO to configure - see GxM0... GxM8 in the deca_regs.h file
|
1163 |
* @param direction - this sets the GPIO direction - see GxP0... GxP8 in the deca_regs.h file
|
1164 |
*
|
1165 |
* output parameters
|
1166 |
*
|
1167 |
* no return value
|
1168 |
*/
|
1169 |
void dwt_setgpiodirection(uint32_t gpioNum, uint32_t direction)
|
1170 |
{ |
1171 |
uint8_t buf[GPIO_DIR_LEN]; |
1172 |
uint32_t command = direction | gpioNum; |
1173 |
|
1174 |
buf[0] = command & 0xff; |
1175 |
buf[1] = (command >> 8) & 0xff; |
1176 |
buf[2] = (command >> 16) & 0xff; |
1177 |
|
1178 |
dwt_writetodevice(GPIO_CTRL_ID, GPIO_DIR_OFFSET, GPIO_DIR_LEN, buf); |
1179 |
} |
1180 |
|
1181 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1182 |
* @fn dwt_setgpiovalue()
|
1183 |
*
|
1184 |
* @brief This is used to set GPIO value as (1) or (0) only applies if the GPIO is configured as output
|
1185 |
*
|
1186 |
* input parameters
|
1187 |
* @param gpioNum - this is the GPIO to configure - see GxM0... GxM8 in the deca_regs.h file
|
1188 |
* @param value - this sets the GPIO value - see GDP0... GDP8 in the deca_regs.h file
|
1189 |
*
|
1190 |
* output parameters
|
1191 |
*
|
1192 |
* no return value
|
1193 |
*/
|
1194 |
void dwt_setgpiovalue(uint32_t gpioNum, uint32_t value)
|
1195 |
{ |
1196 |
uint8_t buf[GPIO_DOUT_LEN]; |
1197 |
uint32_t command = value | gpioNum; |
1198 |
|
1199 |
buf[0] = command & 0xff; |
1200 |
buf[1] = (command >> 8) & 0xff; |
1201 |
buf[2] = (command >> 16) & 0xff; |
1202 |
|
1203 |
dwt_writetodevice(GPIO_CTRL_ID, GPIO_DOUT_OFFSET, GPIO_DOUT_LEN, buf); |
1204 |
} |
1205 |
|
1206 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1207 |
* @fn dwt_getpartid()
|
1208 |
*
|
1209 |
* @brief This is used to return the read part ID of the device
|
1210 |
*
|
1211 |
* NOTE: dwt_initialise() must be called prior to this function so that it can return a relevant value.
|
1212 |
*
|
1213 |
* input parameters
|
1214 |
*
|
1215 |
* output parameters
|
1216 |
*
|
1217 |
* returns the 32 bit part ID value as programmed in the factory
|
1218 |
*/
|
1219 |
uint32_t dwt_getpartid(void)
|
1220 |
{ |
1221 |
return pdw1000local->partID;
|
1222 |
} |
1223 |
|
1224 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1225 |
* @fn dwt_getlotid()
|
1226 |
*
|
1227 |
* @brief This is used to return the read lot ID of the device
|
1228 |
*
|
1229 |
* NOTE: dwt_initialise() must be called prior to this function so that it can return a relevant value.
|
1230 |
*
|
1231 |
* input parameters
|
1232 |
*
|
1233 |
* output parameters
|
1234 |
*
|
1235 |
* returns the 32 bit lot ID value as programmed in the factory
|
1236 |
*/
|
1237 |
uint32_t dwt_getlotid(void)
|
1238 |
{ |
1239 |
return pdw1000local->lotID;
|
1240 |
} |
1241 |
|
1242 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1243 |
* @fn dwt_readdevid()
|
1244 |
*
|
1245 |
* @brief This is used to return the read device type and revision information of the DW1000 device (MP part is 0xDECA0130)
|
1246 |
*
|
1247 |
* input parameters
|
1248 |
*
|
1249 |
* output parameters
|
1250 |
*
|
1251 |
* returns the read value which for DW1000 is 0xDECA0130
|
1252 |
*/
|
1253 |
uint32_t dwt_readdevid(void)
|
1254 |
{ |
1255 |
return dwt_read32bitoffsetreg(DEV_ID_ID,0); |
1256 |
} |
1257 |
|
1258 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1259 |
* @fn dwt_configuretxrf()
|
1260 |
*
|
1261 |
* @brief This function provides the API for the configuration of the TX spectrum
|
1262 |
* including the power and pulse generator delay. The input is a pointer to the data structure
|
1263 |
* of type dwt_txconfig_t that holds all the configurable items.
|
1264 |
*
|
1265 |
* input parameters
|
1266 |
* @param config - pointer to the txrf configuration structure, which contains the tx rf config data
|
1267 |
*
|
1268 |
* output parameters
|
1269 |
*
|
1270 |
* no return value
|
1271 |
*/
|
1272 |
void dwt_configuretxrf(dwt_txconfig_t* config)
|
1273 |
{ |
1274 |
|
1275 |
// Configure RF TX PG_DELAY
|
1276 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGDELAY_OFFSET, config->PGdly); |
1277 |
|
1278 |
// Configure TX power
|
1279 |
dwt_write32bitreg(TX_POWER_ID, config->power); |
1280 |
|
1281 |
} |
1282 |
|
1283 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1284 |
* @fn dwt_configure()
|
1285 |
*
|
1286 |
* @brief This function provides the main API for the configuration of the
|
1287 |
* DW1000 and this low-level driver. The input is a pointer to the data structure
|
1288 |
* of type dwt_config_t that holds all the configurable items.
|
1289 |
* The dwt_config_t structure shows which ones are supported
|
1290 |
*
|
1291 |
* input parameters
|
1292 |
* @param config - pointer to the configuration structure, which contains the device configuration data.
|
1293 |
*
|
1294 |
* output parameters
|
1295 |
*
|
1296 |
* no return value
|
1297 |
*/
|
1298 |
void dwt_configure(dwt_config_t *config)
|
1299 |
{ |
1300 |
uint8_t nsSfd_result = 0;
|
1301 |
uint8_t useDWnsSFD = 0;
|
1302 |
uint8_t chan = config->chan ; |
1303 |
uint32_t regval ; |
1304 |
uint16_t reg16 = lde_replicaCoeff[config->rxCode]; |
1305 |
uint8_t prfIndex = config->prf - DWT_PRF_16M; |
1306 |
uint8_t bw = ((chan == 4) || (chan == 7)) ? 1 : 0 ; // Select wide or narrow band |
1307 |
|
1308 |
#ifdef DWT_API_ERROR_CHECK
|
1309 |
assert(config->dataRate <= DWT_BR_6M8); |
1310 |
assert(config->rxPAC <= DWT_PAC64); |
1311 |
assert((chan >= 1) && (chan <= 7) && (chan != 6)); |
1312 |
assert(((config->prf == DWT_PRF_64M) && (config->txCode >= 9) && (config->txCode <= 24)) |
1313 |
|| ((config->prf == DWT_PRF_16M) && (config->txCode >= 1) && (config->txCode <= 8))); |
1314 |
assert(((config->prf == DWT_PRF_64M) && (config->rxCode >= 9) && (config->rxCode <= 24)) |
1315 |
|| ((config->prf == DWT_PRF_16M) && (config->rxCode >= 1) && (config->rxCode <= 8))); |
1316 |
assert((config->txPreambLength == DWT_PLEN_64) || (config->txPreambLength == DWT_PLEN_128) || (config->txPreambLength == DWT_PLEN_256) |
1317 |
|| (config->txPreambLength == DWT_PLEN_512) || (config->txPreambLength == DWT_PLEN_1024) || (config->txPreambLength == DWT_PLEN_1536) |
1318 |
|| (config->txPreambLength == DWT_PLEN_2048) || (config->txPreambLength == DWT_PLEN_4096)); |
1319 |
assert((config->phrMode == DWT_PHRMODE_STD) || (config->phrMode == DWT_PHRMODE_EXT)); |
1320 |
#endif
|
1321 |
|
1322 |
// For 110 kbps we need a special setup
|
1323 |
if(DWT_BR_110K == config->dataRate)
|
1324 |
{ |
1325 |
pdw1000local->sysCFGreg |= SYS_CFG_RXM110K ; |
1326 |
reg16 >>= 3; // lde_replicaCoeff must be divided by 8 |
1327 |
} |
1328 |
else
|
1329 |
{ |
1330 |
pdw1000local->sysCFGreg &= (~SYS_CFG_RXM110K) ; |
1331 |
} |
1332 |
|
1333 |
pdw1000local->longFrames = config->phrMode ; |
1334 |
|
1335 |
pdw1000local->sysCFGreg &= ~SYS_CFG_PHR_MODE_11; |
1336 |
pdw1000local->sysCFGreg |= (SYS_CFG_PHR_MODE_11 & (uint32_t)(config->phrMode << SYS_CFG_PHR_MODE_SHFT)); |
1337 |
|
1338 |
dwt_write32bitreg(SYS_CFG_ID,pdw1000local->sysCFGreg) ; |
1339 |
// Set the lde_replicaCoeff
|
1340 |
dwt_write16bitoffsetreg(LDE_IF_ID, LDE_REPC_OFFSET, reg16) ; |
1341 |
|
1342 |
_dwt_configlde(prfIndex); |
1343 |
|
1344 |
// Configure PLL2/RF PLL block CFG/TUNE (for a given channel)
|
1345 |
dwt_write32bitoffsetreg(FS_CTRL_ID, FS_PLLCFG_OFFSET, fs_pll_cfg[chan_idx[chan]]); |
1346 |
dwt_write8bitoffsetreg(FS_CTRL_ID, FS_PLLTUNE_OFFSET, fs_pll_tune[chan_idx[chan]]); |
1347 |
|
1348 |
// Configure RF RX blocks (for specified channel/bandwidth)
|
1349 |
dwt_write8bitoffsetreg(RF_CONF_ID, RF_RXCTRLH_OFFSET, rx_config[bw]); |
1350 |
|
1351 |
// Configure RF TX blocks (for specified channel and PRF)
|
1352 |
// Configure RF TX control
|
1353 |
dwt_write32bitoffsetreg(RF_CONF_ID, RF_TXCTRL_OFFSET, tx_config[chan_idx[chan]]); |
1354 |
|
1355 |
// Configure the baseband parameters (for specified PRF, bit rate, PAC, and SFD settings)
|
1356 |
// DTUNE0
|
1357 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_TUNE0b_OFFSET, sftsh[config->dataRate][config->nsSFD]); |
1358 |
|
1359 |
// DTUNE1
|
1360 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_TUNE1a_OFFSET, dtune1[prfIndex]); |
1361 |
|
1362 |
if(config->dataRate == DWT_BR_110K)
|
1363 |
{ |
1364 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_TUNE1b_OFFSET, DRX_TUNE1b_110K); |
1365 |
} |
1366 |
else
|
1367 |
{ |
1368 |
if(config->txPreambLength == DWT_PLEN_64)
|
1369 |
{ |
1370 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_TUNE1b_OFFSET, DRX_TUNE1b_6M8_PRE64); |
1371 |
dwt_write8bitoffsetreg(DRX_CONF_ID, DRX_TUNE4H_OFFSET, DRX_TUNE4H_PRE64); |
1372 |
} |
1373 |
else
|
1374 |
{ |
1375 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_TUNE1b_OFFSET, DRX_TUNE1b_850K_6M8); |
1376 |
dwt_write8bitoffsetreg(DRX_CONF_ID, DRX_TUNE4H_OFFSET, DRX_TUNE4H_PRE128PLUS); |
1377 |
} |
1378 |
} |
1379 |
|
1380 |
// DTUNE2
|
1381 |
dwt_write32bitoffsetreg(DRX_CONF_ID, DRX_TUNE2_OFFSET, digital_bb_config[prfIndex][config->rxPAC]); |
1382 |
|
1383 |
// DTUNE3 (SFD timeout)
|
1384 |
// Don't allow 0 - SFD timeout will always be enabled
|
1385 |
if(config->sfdTO == 0) |
1386 |
{ |
1387 |
config->sfdTO = DWT_SFDTOC_DEF; |
1388 |
} |
1389 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_SFDTOC_OFFSET, config->sfdTO); |
1390 |
|
1391 |
// Configure AGC parameters
|
1392 |
dwt_write32bitoffsetreg( AGC_CFG_STS_ID, 0xC, agc_config.lo32);
|
1393 |
dwt_write16bitoffsetreg( AGC_CFG_STS_ID, 0x4, agc_config.target[prfIndex]);
|
1394 |
|
1395 |
// Set (non-standard) user SFD for improved performance,
|
1396 |
if(config->nsSFD)
|
1397 |
{ |
1398 |
// Write non standard (DW) SFD length
|
1399 |
dwt_write8bitoffsetreg(USR_SFD_ID, 0x00, dwnsSFDlen[config->dataRate]);
|
1400 |
nsSfd_result = 3 ;
|
1401 |
useDWnsSFD = 1 ;
|
1402 |
} |
1403 |
regval = (CHAN_CTRL_TX_CHAN_MASK & (uint32_t)(chan << CHAN_CTRL_TX_CHAN_SHIFT)) | // Transmit Channel
|
1404 |
(CHAN_CTRL_RX_CHAN_MASK & (uint32_t)(chan << CHAN_CTRL_RX_CHAN_SHIFT)) | // Receive Channel
|
1405 |
(CHAN_CTRL_RXFPRF_MASK & (uint32_t)(config->prf << CHAN_CTRL_RXFPRF_SHIFT)) | // RX PRF
|
1406 |
((CHAN_CTRL_TNSSFD|CHAN_CTRL_RNSSFD) & (uint32_t)(nsSfd_result << CHAN_CTRL_TNSSFD_SHIFT)) | // nsSFD enable RX&TX
|
1407 |
(CHAN_CTRL_DWSFD & (uint32_t)(useDWnsSFD << CHAN_CTRL_DWSFD_SHIFT)) | // Use DW nsSFD
|
1408 |
(CHAN_CTRL_TX_PCOD_MASK & (uint32_t)(config->txCode << CHAN_CTRL_TX_PCOD_SHIFT)) | // TX Preamble Code
|
1409 |
(CHAN_CTRL_RX_PCOD_MASK & (uint32_t)(config->rxCode << CHAN_CTRL_RX_PCOD_SHIFT)) ; // RX Preamble Code
|
1410 |
|
1411 |
dwt_write32bitreg(CHAN_CTRL_ID,regval) ; |
1412 |
|
1413 |
// Set up TX Preamble Size, PRF and Data Rate
|
1414 |
pdw1000local->txFCTRL = (uint32_t)(((config->txPreambLength | config->prf) << TX_FCTRL_TXPRF_SHFT) | (config->dataRate << TX_FCTRL_TXBR_SHFT)); |
1415 |
dwt_write32bitreg(TX_FCTRL_ID, pdw1000local->txFCTRL); |
1416 |
|
1417 |
// The SFD transmit pattern is initialised by the DW1000 upon a user TX request, but (due to an IC issue) it is not done for an auto-ACK TX. The
|
1418 |
// SYS_CTRL write below works around this issue, by simultaneously initiating and aborting a transmission, which correctly initialises the SFD
|
1419 |
// after its configuration or reconfiguration.
|
1420 |
// This issue is not documented at the time of writing this code. It should be in next release of DW1000 User Manual (v2.09, from July 2016).
|
1421 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, SYS_CTRL_TXSTRT | SYS_CTRL_TRXOFF); // Request TX start and TRX off at the same time
|
1422 |
} // end dwt_configure()
|
1423 |
|
1424 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1425 |
* @fn dwt_setrxantennadelay()
|
1426 |
*
|
1427 |
* @brief This API function writes the antenna delay (in time units) to RX registers
|
1428 |
*
|
1429 |
* input parameters:
|
1430 |
* @param rxDelay - this is the total (RX) antenna delay value, which
|
1431 |
* will be programmed into the RX register
|
1432 |
*
|
1433 |
* output parameters
|
1434 |
*
|
1435 |
* no return value
|
1436 |
*/
|
1437 |
void dwt_setrxantennadelay(uint16_t rxDelay)
|
1438 |
{ |
1439 |
// Set the RX antenna delay for auto TX timestamp adjustment
|
1440 |
dwt_write16bitoffsetreg(LDE_IF_ID, LDE_RXANTD_OFFSET, rxDelay); |
1441 |
} |
1442 |
|
1443 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1444 |
* @fn dwt_settxantennadelay()
|
1445 |
*
|
1446 |
* @brief This API function writes the antenna delay (in time units) to TX registers
|
1447 |
*
|
1448 |
* input parameters:
|
1449 |
* @param txDelay - this is the total (TX) antenna delay value, which
|
1450 |
* will be programmed into the TX delay register
|
1451 |
*
|
1452 |
* output parameters
|
1453 |
*
|
1454 |
* no return value
|
1455 |
*/
|
1456 |
void dwt_settxantennadelay(uint16_t txDelay)
|
1457 |
{ |
1458 |
// Set the TX antenna delay for auto TX timestamp adjustment
|
1459 |
dwt_write16bitoffsetreg(TX_ANTD_ID, TX_ANTD_OFFSET, txDelay); |
1460 |
} |
1461 |
|
1462 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1463 |
* @fn dwt_writetxdata()
|
1464 |
*
|
1465 |
* @brief This API function writes the supplied TX data into the DW1000's
|
1466 |
* TX buffer. The input parameters are the data length in bytes and a pointer
|
1467 |
* to those data bytes.
|
1468 |
*
|
1469 |
* input parameters
|
1470 |
* @param txFrameLength - This is the total frame length, including the two byte CRC.
|
1471 |
* Note: this is the length of TX message (including the 2 byte CRC) - max is 1023
|
1472 |
* standard PHR mode allows up to 127 bytes
|
1473 |
* if > 127 is programmed, DWT_PHRMODE_EXT needs to be set in the phrMode configuration
|
1474 |
* see dwt_configure function
|
1475 |
* @param txFrameBytes - Pointer to the user’s buffer containing the data to send.
|
1476 |
* @param txBufferOffset - This specifies an offset in the DW1000’s TX Buffer at which to start writing data.
|
1477 |
*
|
1478 |
* output parameters
|
1479 |
*
|
1480 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
1481 |
*/
|
1482 |
int dwt_writetxdata(uint16_t txFrameLength, uint8_t *txFrameBytes, uint16_t txBufferOffset)
|
1483 |
{ |
1484 |
#ifdef DWT_API_ERROR_CHECK
|
1485 |
assert(txFrameLength >= 2);
|
1486 |
assert((pdw1000local->longFrames && (txFrameLength <= 1023)) || (txFrameLength <= 127)); |
1487 |
assert((txBufferOffset + txFrameLength) <= 1024);
|
1488 |
#endif
|
1489 |
|
1490 |
if ((txBufferOffset + txFrameLength) <= 1024) |
1491 |
{ |
1492 |
// Write the data to the IC TX buffer, (-2 bytes for auto generated CRC)
|
1493 |
dwt_writetodevice( TX_BUFFER_ID, txBufferOffset, txFrameLength-2, txFrameBytes);
|
1494 |
return DWT_SUCCESS;
|
1495 |
} |
1496 |
else
|
1497 |
{ |
1498 |
return DWT_ERROR;
|
1499 |
} |
1500 |
} // end dwt_writetxdata()
|
1501 |
|
1502 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1503 |
* @fn dwt_writetxfctrl()
|
1504 |
*
|
1505 |
* @brief This API function configures the TX frame control register before the transmission of a frame
|
1506 |
*
|
1507 |
* input parameters:
|
1508 |
* @param txFrameLength - this is the length of TX message (including the 2 byte CRC) - max is 1023
|
1509 |
* NOTE: standard PHR mode allows up to 127 bytes
|
1510 |
* if > 127 is programmed, DWT_PHRMODE_EXT needs to be set in the phrMode configuration
|
1511 |
* see dwt_configure function
|
1512 |
* @param txBufferOffset - the offset in the tx buffer to start writing the data
|
1513 |
* @param ranging - 1 if this is a ranging frame, else 0
|
1514 |
*
|
1515 |
* output parameters
|
1516 |
*
|
1517 |
* no return value
|
1518 |
*/
|
1519 |
void dwt_writetxfctrl(uint16_t txFrameLength, uint16_t txBufferOffset, int ranging) |
1520 |
{ |
1521 |
|
1522 |
#ifdef DWT_API_ERROR_CHECK
|
1523 |
assert((pdw1000local->longFrames && (txFrameLength <= 1023)) || (txFrameLength <= 127)); |
1524 |
#endif
|
1525 |
|
1526 |
// Write the frame length to the TX frame control register
|
1527 |
// pdw1000local->txFCTRL has kept configured bit rate information
|
1528 |
uint32_t reg32 = pdw1000local->txFCTRL | txFrameLength | (uint16_t)(txBufferOffset << TX_FCTRL_TXBOFFS_SHFT) | (uint16_t)(ranging << TX_FCTRL_TR_SHFT); |
1529 |
dwt_write32bitreg(TX_FCTRL_ID, reg32); |
1530 |
} // end dwt_writetxfctrl()
|
1531 |
|
1532 |
|
1533 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1534 |
* @fn dwt_readrxdata()
|
1535 |
*
|
1536 |
* @brief This is used to read the data from the RX buffer, from an offset location give by offset parameter
|
1537 |
*
|
1538 |
* input parameters
|
1539 |
* @param buffer - the buffer into which the data will be read
|
1540 |
* @param length - the length of data to read (in bytes)
|
1541 |
* @param rxBufferOffset - the offset in the rx buffer from which to read the data
|
1542 |
*
|
1543 |
* output parameters
|
1544 |
*
|
1545 |
* no return value
|
1546 |
*/
|
1547 |
void dwt_readrxdata(uint8_t *buffer, uint16_t length, uint16_t rxBufferOffset)
|
1548 |
{ |
1549 |
dwt_readfromdevice(RX_BUFFER_ID,rxBufferOffset,length,buffer) ; |
1550 |
} |
1551 |
|
1552 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1553 |
* @fn dwt_readaccdata()
|
1554 |
*
|
1555 |
* @brief This is used to read the data from the Accumulator buffer, from an offset location give by offset parameter
|
1556 |
*
|
1557 |
* NOTE: Because of an internal memory access delay when reading the accumulator the first octet output is a dummy octet
|
1558 |
* that should be discarded. This is true no matter what sub-index the read begins at.
|
1559 |
*
|
1560 |
* input parameters
|
1561 |
* @param buffer - the buffer into which the data will be read
|
1562 |
* @param length - the length of data to read (in bytes)
|
1563 |
* @param accOffset - the offset in the acc buffer from which to read the data
|
1564 |
*
|
1565 |
* output parameters
|
1566 |
*
|
1567 |
* no return value
|
1568 |
*/
|
1569 |
void dwt_readaccdata(uint8_t *buffer, uint16_t len, uint16_t accOffset)
|
1570 |
{ |
1571 |
// Force on the ACC clocks if we are sequenced
|
1572 |
_dwt_enableclocks(READ_ACC_ON); |
1573 |
|
1574 |
dwt_readfromdevice(ACC_MEM_ID,accOffset,len,buffer) ; |
1575 |
|
1576 |
_dwt_enableclocks(READ_ACC_OFF); // Revert clocks back
|
1577 |
} |
1578 |
|
1579 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1580 |
* @fn dwt_readdiagnostics()
|
1581 |
*
|
1582 |
* @brief this function reads the RX signal quality diagnostic data
|
1583 |
*
|
1584 |
* input parameters
|
1585 |
* @param diagnostics - diagnostic structure pointer, this will contain the diagnostic data read from the DW1000
|
1586 |
*
|
1587 |
* output parameters
|
1588 |
*
|
1589 |
* no return value
|
1590 |
*/
|
1591 |
void dwt_readdiagnostics(dwt_rxdiag_t *diagnostics)
|
1592 |
{ |
1593 |
// Read the HW FP index
|
1594 |
diagnostics->firstPath = dwt_read16bitoffsetreg(RX_TIME_ID, RX_TIME_FP_INDEX_OFFSET); |
1595 |
|
1596 |
// LDE diagnostic data
|
1597 |
diagnostics->maxNoise = dwt_read16bitoffsetreg(LDE_IF_ID, LDE_THRESH_OFFSET); |
1598 |
|
1599 |
// Read all 8 bytes in one SPI transaction
|
1600 |
dwt_readfromdevice(RX_FQUAL_ID, 0x0, 8, (uint8_t*)&diagnostics->stdNoise); |
1601 |
|
1602 |
diagnostics->firstPathAmp1 = dwt_read16bitoffsetreg(RX_TIME_ID, RX_TIME_FP_AMPL1_OFFSET); |
1603 |
|
1604 |
diagnostics->rxPreamCount = (dwt_read32bitreg(RX_FINFO_ID) & RX_FINFO_RXPACC_MASK) >> RX_FINFO_RXPACC_SHIFT ; |
1605 |
} |
1606 |
|
1607 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1608 |
* @fn dwt_readtxtimestamp()
|
1609 |
*
|
1610 |
* @brief This is used to read the TX timestamp (adjusted with the programmed antenna delay)
|
1611 |
*
|
1612 |
* input parameters
|
1613 |
* @param timestamp - a pointer to a 5-byte buffer which will store the read TX timestamp time
|
1614 |
*
|
1615 |
* output parameters - the timestamp buffer will contain the value after the function call
|
1616 |
*
|
1617 |
* no return value
|
1618 |
*/
|
1619 |
void dwt_readtxtimestamp(uint8_t * timestamp)
|
1620 |
{ |
1621 |
dwt_readfromdevice(TX_TIME_ID, TX_TIME_TX_STAMP_OFFSET, TX_TIME_TX_STAMP_LEN, timestamp) ; // Read bytes directly into buffer
|
1622 |
} |
1623 |
|
1624 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1625 |
* @fn dwt_readtxtimestamphi32()
|
1626 |
*
|
1627 |
* @brief This is used to read the high 32-bits of the TX timestamp (adjusted with the programmed antenna delay)
|
1628 |
*
|
1629 |
* input parameters
|
1630 |
*
|
1631 |
* output parameters
|
1632 |
*
|
1633 |
* returns high 32-bits of TX timestamp
|
1634 |
*/
|
1635 |
uint32_t dwt_readtxtimestamphi32(void)
|
1636 |
{ |
1637 |
return dwt_read32bitoffsetreg(TX_TIME_ID, 1); // Offset is 1 to get the 4 upper bytes out of 5 |
1638 |
} |
1639 |
|
1640 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1641 |
* @fn dwt_readtxtimestamplo32()
|
1642 |
*
|
1643 |
* @brief This is used to read the low 32-bits of the TX timestamp (adjusted with the programmed antenna delay)
|
1644 |
*
|
1645 |
* input parameters
|
1646 |
*
|
1647 |
* output parameters
|
1648 |
*
|
1649 |
* returns low 32-bits of TX timestamp
|
1650 |
*/
|
1651 |
uint32_t dwt_readtxtimestamplo32(void)
|
1652 |
{ |
1653 |
return dwt_read32bitreg(TX_TIME_ID); // Read TX TIME as a 32-bit register to get the 4 lower bytes out of 5 |
1654 |
} |
1655 |
|
1656 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1657 |
* @fn dwt_readrxtimestamp()
|
1658 |
*
|
1659 |
* @brief This is used to read the RX timestamp (adjusted time of arrival)
|
1660 |
*
|
1661 |
* input parameters
|
1662 |
* @param timestamp - a pointer to a 5-byte buffer which will store the read RX timestamp time
|
1663 |
*
|
1664 |
* output parameters - the timestamp buffer will contain the value after the function call
|
1665 |
*
|
1666 |
* no return value
|
1667 |
*/
|
1668 |
void dwt_readrxtimestamp(uint8_t * timestamp)
|
1669 |
{ |
1670 |
dwt_readfromdevice(RX_TIME_ID, RX_TIME_RX_STAMP_OFFSET, RX_TIME_RX_STAMP_LEN, timestamp) ; // Get the adjusted time of arrival
|
1671 |
} |
1672 |
|
1673 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1674 |
* @fn dwt_readrxtimestamphi32()
|
1675 |
*
|
1676 |
* @brief This is used to read the high 32-bits of the RX timestamp (adjusted with the programmed antenna delay)
|
1677 |
*
|
1678 |
* input parameters
|
1679 |
*
|
1680 |
* output parameters
|
1681 |
*
|
1682 |
* returns high 32-bits of RX timestamp
|
1683 |
*/
|
1684 |
uint32_t dwt_readrxtimestamphi32(void)
|
1685 |
{ |
1686 |
return dwt_read32bitoffsetreg(RX_TIME_ID, 1); // Offset is 1 to get the 4 upper bytes out of 5 |
1687 |
} |
1688 |
|
1689 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1690 |
* @fn dwt_readrxtimestamplo32()
|
1691 |
*
|
1692 |
* @brief This is used to read the low 32-bits of the RX timestamp (adjusted with the programmed antenna delay)
|
1693 |
*
|
1694 |
* input parameters
|
1695 |
*
|
1696 |
* output parameters
|
1697 |
*
|
1698 |
* returns low 32-bits of RX timestamp
|
1699 |
*/
|
1700 |
uint32_t dwt_readrxtimestamplo32(void)
|
1701 |
{ |
1702 |
return dwt_read32bitreg(RX_TIME_ID); // Read RX TIME as a 32-bit register to get the 4 lower bytes out of 5 |
1703 |
} |
1704 |
|
1705 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1706 |
* @fn dwt_readsystimestamphi32()
|
1707 |
*
|
1708 |
* @brief This is used to read the high 32-bits of the system time
|
1709 |
*
|
1710 |
* input parameters
|
1711 |
*
|
1712 |
* output parameters
|
1713 |
*
|
1714 |
* returns high 32-bits of system time timestamp
|
1715 |
*/
|
1716 |
uint32_t dwt_readsystimestamphi32(void)
|
1717 |
{ |
1718 |
return dwt_read32bitoffsetreg(SYS_TIME_ID, 1); // Offset is 1 to get the 4 upper bytes out of 5 |
1719 |
} |
1720 |
|
1721 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1722 |
* @fn dwt_readsystime()
|
1723 |
*
|
1724 |
* @brief This is used to read the system time
|
1725 |
*
|
1726 |
* input parameters
|
1727 |
* @param timestamp - a pointer to a 5-byte buffer which will store the read system time
|
1728 |
*
|
1729 |
* output parameters
|
1730 |
* @param timestamp - the timestamp buffer will contain the value after the function call
|
1731 |
*
|
1732 |
* no return value
|
1733 |
*/
|
1734 |
void dwt_readsystime(uint8_t * timestamp)
|
1735 |
{ |
1736 |
dwt_readfromdevice(SYS_TIME_ID, SYS_TIME_OFFSET, SYS_TIME_LEN, timestamp) ; |
1737 |
} |
1738 |
|
1739 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1740 |
* @fn dwt_writetodevice()
|
1741 |
*
|
1742 |
* @brief this function is used to write to the DW1000 device registers
|
1743 |
* Notes:
|
1744 |
* 1. Firstly we create a header (the first byte is a header byte)
|
1745 |
* a. check if sub index is used, if subindexing is used - set bit-6 to 1 to signify that the sub-index address follows the register index byte
|
1746 |
* b. set bit-7 (or with 0x80) for write operation
|
1747 |
* c. if extended sub address index is used (i.e. if index > 127) set bit-7 of the first sub-index byte following the first header byte
|
1748 |
*
|
1749 |
* 2. Write the header followed by the data bytes to the DW1000 device
|
1750 |
*
|
1751 |
*
|
1752 |
* input parameters:
|
1753 |
* @param recordNumber - ID of register file or buffer being accessed
|
1754 |
* @param index - byte index into register file or buffer being accessed
|
1755 |
* @param length - number of bytes being written
|
1756 |
* @param buffer - pointer to buffer containing the 'length' bytes to be written
|
1757 |
*
|
1758 |
* output parameters
|
1759 |
*
|
1760 |
* no return value
|
1761 |
*/
|
1762 |
void dwt_writetodevice
|
1763 |
( |
1764 |
uint16_t recordNumber, |
1765 |
uint16_t index, |
1766 |
uint32_t length, |
1767 |
const uint8_t *buffer
|
1768 |
) |
1769 |
{ |
1770 |
uint8_t header[3] ; // Buffer to compose header in |
1771 |
int cnt = 0; // Counter for length of header |
1772 |
#ifdef DWT_API_ERROR_CHECK
|
1773 |
assert(recordNumber <= 0x3F); // Record number is limited to 6-bits. |
1774 |
#endif
|
1775 |
|
1776 |
// Write message header selecting WRITE operation and addresses as appropriate (this is one to three bytes long)
|
1777 |
if (index == 0) // For index of 0, no sub-index is required |
1778 |
{ |
1779 |
header[cnt++] = 0x80 | (uint8_t)recordNumber ; // Bit-7 is WRITE operation, bit-6 zero=NO sub-addressing, bits 5-0 is reg file id |
1780 |
} |
1781 |
else
|
1782 |
{ |
1783 |
#ifdef DWT_API_ERROR_CHECK
|
1784 |
assert((index <= 0x7FFF) && ((index + length) <= 0x7FFF)); // Index and sub-addressable area are limited to 15-bits. |
1785 |
#endif
|
1786 |
header[cnt++] = 0xC0 | (uint8_t)recordNumber ; // Bit-7 is WRITE operation, bit-6 one=sub-address follows, bits 5-0 is reg file id |
1787 |
|
1788 |
if (index <= 127) // For non-zero index < 127, just a single sub-index byte is required |
1789 |
{ |
1790 |
header[cnt++] = (uint8_t)index ; // Bit-7 zero means no extension, bits 6-0 is index.
|
1791 |
} |
1792 |
else
|
1793 |
{ |
1794 |
header[cnt++] = 0x80 | (uint8_t)(index) ; // Bit-7 one means extended index, bits 6-0 is low seven bits of index. |
1795 |
header[cnt++] = (uint8_t) (index >> 7) ; // 8-bit value = high eight bits of index. |
1796 |
} |
1797 |
} |
1798 |
|
1799 |
// Write it to the SPI
|
1800 |
writetospi((uint16_t)cnt,header,length,buffer); |
1801 |
} // end dwt_writetodevice()
|
1802 |
|
1803 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1804 |
* @fn dwt_readfromdevice()
|
1805 |
*
|
1806 |
* @brief this function is used to read from the DW1000 device registers
|
1807 |
* Notes:
|
1808 |
* 1. Firstly we create a header (the first byte is a header byte)
|
1809 |
* a. check if sub index is used, if subindexing is used - set bit-6 to 1 to signify that the sub-index address follows the register index byte
|
1810 |
* b. set bit-7 (or with 0x80) for write operation
|
1811 |
* c. if extended sub address index is used (i.e. if index > 127) set bit-7 of the first sub-index byte following the first header byte
|
1812 |
*
|
1813 |
* 2. Write the header followed by the data bytes to the DW1000 device
|
1814 |
* 3. Store the read data in the input buffer
|
1815 |
*
|
1816 |
* input parameters:
|
1817 |
* @param recordNumber - ID of register file or buffer being accessed
|
1818 |
* @param index - byte index into register file or buffer being accessed
|
1819 |
* @param length - number of bytes being read
|
1820 |
* @param buffer - pointer to buffer in which to return the read data.
|
1821 |
*
|
1822 |
* output parameters
|
1823 |
*
|
1824 |
* no return value
|
1825 |
*/
|
1826 |
void dwt_readfromdevice
|
1827 |
( |
1828 |
uint16_t recordNumber, |
1829 |
uint16_t index, |
1830 |
uint32_t length, |
1831 |
uint8_t *buffer |
1832 |
) |
1833 |
{ |
1834 |
uint8_t header[3] ; // Buffer to compose header in |
1835 |
int cnt = 0; // Counter for length of header |
1836 |
#ifdef DWT_API_ERROR_CHECK
|
1837 |
assert(recordNumber <= 0x3F); // Record number is limited to 6-bits. |
1838 |
#endif
|
1839 |
|
1840 |
// Write message header selecting READ operation and addresses as appropriate (this is one to three bytes long)
|
1841 |
if (index == 0) // For index of 0, no sub-index is required |
1842 |
{ |
1843 |
header[cnt++] = (uint8_t) recordNumber ; // Bit-7 zero is READ operation, bit-6 zero=NO sub-addressing, bits 5-0 is reg file id
|
1844 |
} |
1845 |
else
|
1846 |
{ |
1847 |
#ifdef DWT_API_ERROR_CHECK
|
1848 |
assert((index <= 0x7FFF) && ((index + length) <= 0x7FFF)); // Index and sub-addressable area are limited to 15-bits. |
1849 |
#endif
|
1850 |
header[cnt++] = (uint8_t)(0x40 | recordNumber) ; // Bit-7 zero is READ operation, bit-6 one=sub-address follows, bits 5-0 is reg file id |
1851 |
|
1852 |
if (index <= 127) // For non-zero index < 127, just a single sub-index byte is required |
1853 |
{ |
1854 |
header[cnt++] = (uint8_t) index ; // Bit-7 zero means no extension, bits 6-0 is index.
|
1855 |
} |
1856 |
else
|
1857 |
{ |
1858 |
header[cnt++] = 0x80 | (uint8_t)(index) ; // Bit-7 one means extended index, bits 6-0 is low seven bits of index. |
1859 |
header[cnt++] = (uint8_t) (index >> 7) ; // 8-bit value = high eight bits of index. |
1860 |
} |
1861 |
} |
1862 |
|
1863 |
// Do the read from the SPI
|
1864 |
readfromspi((uint16_t)cnt, header, length, buffer); |
1865 |
} // end dwt_readfromdevice()
|
1866 |
|
1867 |
|
1868 |
|
1869 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1870 |
* @fn dwt_read32bitoffsetreg()
|
1871 |
*
|
1872 |
* @brief this function is used to read 32-bit value from the DW1000 device registers
|
1873 |
*
|
1874 |
* input parameters:
|
1875 |
* @param regFileID - ID of register file or buffer being accessed
|
1876 |
* @param regOffset - the index into register file or buffer being accessed
|
1877 |
*
|
1878 |
* output parameters
|
1879 |
*
|
1880 |
* returns 32 bit register value
|
1881 |
*/
|
1882 |
uint32_t dwt_read32bitoffsetreg(int regFileID,int regOffset) |
1883 |
{ |
1884 |
uint32_t regval = 0 ;
|
1885 |
int j ;
|
1886 |
uint8_t buffer[4] ;
|
1887 |
|
1888 |
dwt_readfromdevice((uint16_t)regFileID, (uint16_t)regOffset,4,buffer); // Read 4 bytes (32-bits) register into buffer |
1889 |
|
1890 |
for (j = 3 ; j >= 0 ; j --) |
1891 |
{ |
1892 |
regval = (regval << 8) + buffer[j] ;
|
1893 |
} |
1894 |
return regval ;
|
1895 |
|
1896 |
} // end dwt_read32bitoffsetreg()
|
1897 |
|
1898 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1899 |
* @fn dwt_read16bitoffsetreg()
|
1900 |
*
|
1901 |
* @brief this function is used to read 16-bit value from the DW1000 device registers
|
1902 |
*
|
1903 |
* input parameters:
|
1904 |
* @param regFileID - ID of register file or buffer being accessed
|
1905 |
* @param regOffset - the index into register file or buffer being accessed
|
1906 |
*
|
1907 |
* output parameters
|
1908 |
*
|
1909 |
* returns 16 bit register value
|
1910 |
*/
|
1911 |
uint16_t dwt_read16bitoffsetreg(int regFileID,int regOffset) |
1912 |
{ |
1913 |
uint16_t regval = 0 ;
|
1914 |
uint8_t buffer[2] ;
|
1915 |
|
1916 |
dwt_readfromdevice((uint16_t)regFileID, (uint16_t)regOffset,2,buffer); // Read 2 bytes (16-bits) register into buffer |
1917 |
|
1918 |
regval = (uint16_t)((buffer[1] << 8) + buffer[0] ); |
1919 |
return regval ;
|
1920 |
|
1921 |
} // end dwt_read16bitoffsetreg()
|
1922 |
|
1923 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1924 |
* @fn dwt_read8bitoffsetreg()
|
1925 |
*
|
1926 |
* @brief this function is used to read an 8-bit value from the DW1000 device registers
|
1927 |
*
|
1928 |
* input parameters:
|
1929 |
* @param regFileID - ID of register file or buffer being accessed
|
1930 |
* @param regOffset - the index into register file or buffer being accessed
|
1931 |
*
|
1932 |
* output parameters
|
1933 |
*
|
1934 |
* returns 8-bit register value
|
1935 |
*/
|
1936 |
uint8_t dwt_read8bitoffsetreg(int regFileID, int regOffset) |
1937 |
{ |
1938 |
uint8_t regval; |
1939 |
|
1940 |
dwt_readfromdevice((uint16_t)regFileID, (uint16_t)regOffset, 1, ®val);
|
1941 |
|
1942 |
return regval ;
|
1943 |
} |
1944 |
|
1945 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1946 |
* @fn dwt_write8bitoffsetreg()
|
1947 |
*
|
1948 |
* @brief this function is used to write an 8-bit value to the DW1000 device registers
|
1949 |
*
|
1950 |
* input parameters:
|
1951 |
* @param regFileID - ID of register file or buffer being accessed
|
1952 |
* @param regOffset - the index into register file or buffer being accessed
|
1953 |
* @param regval - the value to write
|
1954 |
*
|
1955 |
* output parameters
|
1956 |
*
|
1957 |
* no return value
|
1958 |
*/
|
1959 |
void dwt_write8bitoffsetreg(int regFileID, int regOffset, uint8_t regval) |
1960 |
{ |
1961 |
dwt_writetodevice((uint16_t)regFileID, (uint16_t)regOffset, 1, ®val);
|
1962 |
} |
1963 |
|
1964 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1965 |
* @fn dwt_write16bitoffsetreg()
|
1966 |
*
|
1967 |
* @brief this function is used to write 16-bit value to the DW1000 device registers
|
1968 |
*
|
1969 |
* input parameters:
|
1970 |
* @param regFileID - ID of register file or buffer being accessed
|
1971 |
* @param regOffset - the index into register file or buffer being accessed
|
1972 |
* @param regval - the value to write
|
1973 |
*
|
1974 |
* output parameters
|
1975 |
*
|
1976 |
* no return value
|
1977 |
*/
|
1978 |
void dwt_write16bitoffsetreg(int regFileID,int regOffset,uint16_t regval) |
1979 |
{ |
1980 |
uint8_t buffer[2] ;
|
1981 |
|
1982 |
buffer[0] = regval & 0xFF; |
1983 |
buffer[1] = regval >> 8 ; |
1984 |
|
1985 |
dwt_writetodevice((uint16_t)regFileID, (uint16_t)regOffset,2,buffer);
|
1986 |
} // end dwt_write16bitoffsetreg()
|
1987 |
|
1988 |
/*! ------------------------------------------------------------------------------------------------------------------
|
1989 |
* @fn dwt_write32bitoffsetreg()
|
1990 |
*
|
1991 |
* @brief this function is used to write 32-bit value to the DW1000 device registers
|
1992 |
*
|
1993 |
* input parameters:
|
1994 |
* @param regFileID - ID of register file or buffer being accessed
|
1995 |
* @param regOffset - the index into register file or buffer being accessed
|
1996 |
* @param regval - the value to write
|
1997 |
*
|
1998 |
* output parameters
|
1999 |
*
|
2000 |
* no return value
|
2001 |
*/
|
2002 |
void dwt_write32bitoffsetreg(int regFileID,int regOffset,uint32_t regval) |
2003 |
{ |
2004 |
int j ;
|
2005 |
uint8_t buffer[4] ;
|
2006 |
|
2007 |
for ( j = 0 ; j < 4 ; j++ ) |
2008 |
{ |
2009 |
buffer[j] = regval & 0xff ;
|
2010 |
regval >>= 8 ;
|
2011 |
} |
2012 |
|
2013 |
dwt_writetodevice((uint16_t)regFileID,(uint16_t)regOffset,4,buffer);
|
2014 |
} // end dwt_write32bitoffsetreg()
|
2015 |
|
2016 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2017 |
* @fn dwt_enableframefilter()
|
2018 |
*
|
2019 |
* @brief This is used to enable the frame filtering - (the default option is to
|
2020 |
* accept any data and ACK frames with correct destination address
|
2021 |
*
|
2022 |
* input parameters
|
2023 |
* @param - bitmask - enables/disables the frame filtering options according to
|
2024 |
* DWT_FF_NOTYPE_EN 0x000 no frame types allowed
|
2025 |
* DWT_FF_COORD_EN 0x002 behave as coordinator (can receive frames with no destination address (PAN ID has to match))
|
2026 |
* DWT_FF_BEACON_EN 0x004 beacon frames allowed
|
2027 |
* DWT_FF_DATA_EN 0x008 data frames allowed
|
2028 |
* DWT_FF_ACK_EN 0x010 ack frames allowed
|
2029 |
* DWT_FF_MAC_EN 0x020 mac control frames allowed
|
2030 |
* DWT_FF_RSVD_EN 0x040 reserved frame types allowed
|
2031 |
*
|
2032 |
* output parameters
|
2033 |
*
|
2034 |
* no return value
|
2035 |
*/
|
2036 |
void dwt_enableframefilter(uint16_t enable)
|
2037 |
{ |
2038 |
uint32_t sysconfig = SYS_CFG_MASK & dwt_read32bitreg(SYS_CFG_ID) ; // Read sysconfig register
|
2039 |
|
2040 |
if(enable)
|
2041 |
{ |
2042 |
// Enable frame filtering and configure frame types
|
2043 |
sysconfig &= ~(SYS_CFG_FF_ALL_EN); // Clear all
|
2044 |
sysconfig |= (enable & SYS_CFG_FF_ALL_EN) | SYS_CFG_FFE; |
2045 |
} |
2046 |
else
|
2047 |
{ |
2048 |
sysconfig &= ~(SYS_CFG_FFE); |
2049 |
} |
2050 |
|
2051 |
pdw1000local->sysCFGreg = sysconfig ; |
2052 |
dwt_write32bitreg(SYS_CFG_ID,sysconfig) ; |
2053 |
} |
2054 |
|
2055 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2056 |
* @fn dwt_setpanid()
|
2057 |
*
|
2058 |
* @brief This is used to set the PAN ID
|
2059 |
*
|
2060 |
* input parameters
|
2061 |
* @param panID - this is the PAN ID
|
2062 |
*
|
2063 |
* output parameters
|
2064 |
*
|
2065 |
* no return value
|
2066 |
*/
|
2067 |
void dwt_setpanid(uint16_t panID)
|
2068 |
{ |
2069 |
// PAN ID is high 16 bits of register
|
2070 |
dwt_write16bitoffsetreg(PANADR_ID, PANADR_PAN_ID_OFFSET, panID); |
2071 |
} |
2072 |
|
2073 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2074 |
* @fn dwt_setaddress16()
|
2075 |
*
|
2076 |
* @brief This is used to set 16-bit (short) address
|
2077 |
*
|
2078 |
* input parameters
|
2079 |
* @param shortAddress - this sets the 16 bit short address
|
2080 |
*
|
2081 |
* output parameters
|
2082 |
*
|
2083 |
* no return value
|
2084 |
*/
|
2085 |
void dwt_setaddress16(uint16_t shortAddress)
|
2086 |
{ |
2087 |
// Short address into low 16 bits
|
2088 |
dwt_write16bitoffsetreg(PANADR_ID, PANADR_SHORT_ADDR_OFFSET, shortAddress); |
2089 |
} |
2090 |
|
2091 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2092 |
* @fn dwt_seteui()
|
2093 |
*
|
2094 |
* @brief This is used to set the EUI 64-bit (long) address
|
2095 |
*
|
2096 |
* input parameters
|
2097 |
* @param eui64 - this is the pointer to a buffer that contains the 64bit address
|
2098 |
*
|
2099 |
* output parameters
|
2100 |
*
|
2101 |
* no return value
|
2102 |
*/
|
2103 |
void dwt_seteui(uint8_t *eui64)
|
2104 |
{ |
2105 |
dwt_writetodevice(EUI_64_ID, EUI_64_OFFSET, EUI_64_LEN, eui64); |
2106 |
} |
2107 |
|
2108 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2109 |
* @fn dwt_geteui()
|
2110 |
*
|
2111 |
* @brief This is used to get the EUI 64-bit from the DW1000
|
2112 |
*
|
2113 |
* input parameters
|
2114 |
* @param eui64 - this is the pointer to a buffer that will contain the read 64-bit EUI value
|
2115 |
*
|
2116 |
* output parameters
|
2117 |
*
|
2118 |
* no return value
|
2119 |
*/
|
2120 |
void dwt_geteui(uint8_t *eui64)
|
2121 |
{ |
2122 |
dwt_readfromdevice(EUI_64_ID, EUI_64_OFFSET, EUI_64_LEN, eui64); |
2123 |
} |
2124 |
|
2125 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2126 |
* @fn dwt_otpread()
|
2127 |
*
|
2128 |
* @brief This is used to read the OTP data from given address into provided array
|
2129 |
*
|
2130 |
* input parameters
|
2131 |
* @param address - this is the OTP address to read from
|
2132 |
* @param array - this is the pointer to the array into which to read the data
|
2133 |
* @param length - this is the number of 32 bit words to read (array needs to be at least this length)
|
2134 |
*
|
2135 |
* output parameters
|
2136 |
*
|
2137 |
* no return value
|
2138 |
*/
|
2139 |
void dwt_otpread(uint32_t address, uint32_t *array, uint8_t length)
|
2140 |
{ |
2141 |
int i;
|
2142 |
|
2143 |
_dwt_enableclocks(FORCE_SYS_XTI); // NOTE: Set system clock to XTAL - this is necessary to make sure the values read by _dwt_otpread are reliable
|
2144 |
|
2145 |
for(i=0; i<length; i++) |
2146 |
{ |
2147 |
array[i] = _dwt_otpread(address + (uint32_t)i) ; |
2148 |
} |
2149 |
|
2150 |
_dwt_enableclocks(ENABLE_ALL_SEQ); // Restore system clock to PLL
|
2151 |
|
2152 |
return ;
|
2153 |
} |
2154 |
|
2155 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2156 |
* @fn _dwt_otpread()
|
2157 |
*
|
2158 |
* @brief function to read the OTP memory. Ensure that MR,MRa,MRb are reset to 0.
|
2159 |
*
|
2160 |
* input parameters
|
2161 |
* @param address - address to read at
|
2162 |
*
|
2163 |
* output parameters
|
2164 |
*
|
2165 |
* returns the 32bit of read data
|
2166 |
*/
|
2167 |
uint32_t _dwt_otpread(uint32_t address) |
2168 |
{ |
2169 |
uint32_t ret_data; |
2170 |
|
2171 |
// Write the address
|
2172 |
dwt_write16bitoffsetreg(OTP_IF_ID, OTP_ADDR, (uint16_t)address); |
2173 |
|
2174 |
// Perform OTP Read - Manual read mode has to be set
|
2175 |
dwt_write8bitoffsetreg(OTP_IF_ID, OTP_CTRL, OTP_CTRL_OTPREAD | OTP_CTRL_OTPRDEN); |
2176 |
dwt_write8bitoffsetreg(OTP_IF_ID, OTP_CTRL, 0x00); // OTPREAD is self clearing but OTPRDEN is not |
2177 |
|
2178 |
// Read read data, available 40ns after rising edge of OTP_READ
|
2179 |
ret_data = dwt_read32bitoffsetreg(OTP_IF_ID, OTP_RDAT); |
2180 |
|
2181 |
// Return the 32bit of read data
|
2182 |
return ret_data;
|
2183 |
} |
2184 |
|
2185 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2186 |
* @fn _dwt_otpsetmrregs()
|
2187 |
*
|
2188 |
* @brief Configure the MR registers for initial programming (enable charge pump).
|
2189 |
* Read margin is used to stress the read back from the
|
2190 |
* programmed bit. In normal operation this is relaxed.
|
2191 |
*
|
2192 |
* input parameters
|
2193 |
* @param mode - "0" : Reset all to 0x0: MRA=0x0000, MRB=0x0000, MR=0x0000
|
2194 |
* "1" : Set for inital programming: MRA=0x9220, MRB=0x000E, MR=0x1024
|
2195 |
* "2" : Set for soak programming: MRA=0x9220, MRB=0x0003, MR=0x1824
|
2196 |
* "3" : High Vpp: MRA=0x9220, MRB=0x004E, MR=0x1824
|
2197 |
* "4" : Low Read Margin: MRA=0x0000, MRB=0x0003, MR=0x0000
|
2198 |
* "5" : Array Clean: MRA=0x0049, MRB=0x0003, MR=0x0024
|
2199 |
* "4" : Very Low Read Margin: MRA=0x0000, MRB=0x0003, MR=0x0000
|
2200 |
*
|
2201 |
* output parameters
|
2202 |
*
|
2203 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
2204 |
*/
|
2205 |
int32_t _dwt_otpsetmrregs(int mode)
|
2206 |
{ |
2207 |
uint8_t rd_buf[4];
|
2208 |
uint8_t wr_buf[4];
|
2209 |
uint32_t mra=0,mrb=0,mr=0; |
2210 |
|
2211 |
// PROGRAMME MRA
|
2212 |
// Set MRA, MODE_SEL
|
2213 |
wr_buf[0] = 0x03; |
2214 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL+1,1,wr_buf); |
2215 |
|
2216 |
// Load data
|
2217 |
switch(mode&0x0f) { |
2218 |
case 0x0 : |
2219 |
mr =0x0000;
|
2220 |
mra=0x0000;
|
2221 |
mrb=0x0000;
|
2222 |
break;
|
2223 |
case 0x1 : |
2224 |
mr =0x1024;
|
2225 |
mra=0x9220; // Enable CPP mon |
2226 |
mrb=0x000e;
|
2227 |
break;
|
2228 |
case 0x2 : |
2229 |
mr =0x1824;
|
2230 |
mra=0x9220;
|
2231 |
mrb=0x0003;
|
2232 |
break;
|
2233 |
case 0x3 : |
2234 |
mr =0x1824;
|
2235 |
mra=0x9220;
|
2236 |
mrb=0x004e;
|
2237 |
break;
|
2238 |
case 0x4 : |
2239 |
mr =0x0000;
|
2240 |
mra=0x0000;
|
2241 |
mrb=0x0003;
|
2242 |
break;
|
2243 |
case 0x5 : |
2244 |
mr =0x0024;
|
2245 |
mra=0x0000;
|
2246 |
mrb=0x0003;
|
2247 |
break;
|
2248 |
default :
|
2249 |
return DWT_ERROR;
|
2250 |
} |
2251 |
|
2252 |
wr_buf[0] = mra & 0x00ff; |
2253 |
wr_buf[1] = (mra & 0xff00)>>8; |
2254 |
dwt_writetodevice(OTP_IF_ID, OTP_WDAT,2,wr_buf);
|
2255 |
|
2256 |
|
2257 |
// Set WRITE_MR
|
2258 |
wr_buf[0] = 0x08; |
2259 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2260 |
|
2261 |
// Wait?
|
2262 |
|
2263 |
// Set Clear Mode sel
|
2264 |
wr_buf[0] = 0x02; |
2265 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2266 |
|
2267 |
// Set AUX update, write MR
|
2268 |
wr_buf[0] = 0x88; |
2269 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2270 |
// Clear write MR
|
2271 |
wr_buf[0] = 0x80; |
2272 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2273 |
// Clear AUX update
|
2274 |
wr_buf[0] = 0x00; |
2275 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2276 |
|
2277 |
///////////////////////////////////////////
|
2278 |
// PROGRAM MRB
|
2279 |
// Set SLOW, MRB, MODE_SEL
|
2280 |
wr_buf[0] = 0x05; |
2281 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2282 |
|
2283 |
wr_buf[0] = mrb & 0x00ff; |
2284 |
wr_buf[1] = (mrb & 0xff00)>>8; |
2285 |
dwt_writetodevice(OTP_IF_ID, OTP_WDAT,2,wr_buf);
|
2286 |
|
2287 |
// Set WRITE_MR
|
2288 |
wr_buf[0] = 0x08; |
2289 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2290 |
|
2291 |
// Wait?
|
2292 |
|
2293 |
// Set Clear Mode sel
|
2294 |
wr_buf[0] = 0x04; |
2295 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2296 |
|
2297 |
// Set AUX update, write MR
|
2298 |
wr_buf[0] = 0x88; |
2299 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2300 |
// Clear write MR
|
2301 |
wr_buf[0] = 0x80; |
2302 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2303 |
// Clear AUX update
|
2304 |
wr_buf[0] = 0x00; |
2305 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2306 |
|
2307 |
///////////////////////////////////////////
|
2308 |
// PROGRAM MR
|
2309 |
// Set SLOW, MODE_SEL
|
2310 |
wr_buf[0] = 0x01; |
2311 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2312 |
// Load data
|
2313 |
|
2314 |
wr_buf[0] = mr & 0x00ff; |
2315 |
wr_buf[1] = (mr & 0xff00)>>8; |
2316 |
dwt_writetodevice(OTP_IF_ID, OTP_WDAT,2,wr_buf);
|
2317 |
|
2318 |
// Set WRITE_MR
|
2319 |
wr_buf[0] = 0x08; |
2320 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2321 |
|
2322 |
// Wait?
|
2323 |
deca_sleep(10);
|
2324 |
// Set Clear Mode sel
|
2325 |
wr_buf[0] = 0x00; |
2326 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2327 |
|
2328 |
// Read confirm mode writes.
|
2329 |
// Set man override, MRA_SEL
|
2330 |
wr_buf[0] = OTP_CTRL_OTPRDEN;
|
2331 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2332 |
wr_buf[0] = 0x02; |
2333 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2334 |
// MRB_SEL
|
2335 |
wr_buf[0] = 0x04; |
2336 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2337 |
deca_sleep(100);
|
2338 |
|
2339 |
// Clear mode sel
|
2340 |
wr_buf[0] = 0x00; |
2341 |
dwt_writetodevice(OTP_IF_ID,OTP_CTRL+1,1,wr_buf); |
2342 |
// Clear MAN_OVERRIDE
|
2343 |
wr_buf[0] = 0x00; |
2344 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL,1,wr_buf);
|
2345 |
|
2346 |
deca_sleep(10);
|
2347 |
|
2348 |
if (((mode&0x0f) == 0x1)||((mode&0x0f) == 0x2)) |
2349 |
{ |
2350 |
// Read status register
|
2351 |
dwt_readfromdevice(OTP_IF_ID, OTP_STAT,1,rd_buf);
|
2352 |
} |
2353 |
|
2354 |
return DWT_SUCCESS;
|
2355 |
} |
2356 |
|
2357 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2358 |
* @fn _dwt_otpprogword32()
|
2359 |
*
|
2360 |
* @brief function to program the OTP memory. Ensure that MR,MRa,MRb are reset to 0.
|
2361 |
* VNM Charge pump needs to be enabled (see _dwt_otpsetmrregs)
|
2362 |
* Note the address is only 11 bits long.
|
2363 |
*
|
2364 |
* input parameters
|
2365 |
* @param address - address to read at
|
2366 |
*
|
2367 |
* output parameters
|
2368 |
*
|
2369 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
2370 |
*/
|
2371 |
int32_t _dwt_otpprogword32(uint32_t data, uint16_t address) |
2372 |
{ |
2373 |
uint8_t rd_buf[1];
|
2374 |
uint8_t wr_buf[4];
|
2375 |
uint8_t otp_done; |
2376 |
|
2377 |
// Read status register
|
2378 |
dwt_readfromdevice(OTP_IF_ID, OTP_STAT, 1, rd_buf);
|
2379 |
|
2380 |
if((rd_buf[0] & 0x02) != 0x02) |
2381 |
{ |
2382 |
return DWT_ERROR;
|
2383 |
} |
2384 |
|
2385 |
// Write the data
|
2386 |
wr_buf[3] = (data>>24) & 0xff; |
2387 |
wr_buf[2] = (data>>16) & 0xff; |
2388 |
wr_buf[1] = (data>>8) & 0xff; |
2389 |
wr_buf[0] = data & 0xff; |
2390 |
dwt_writetodevice(OTP_IF_ID, OTP_WDAT, 4, wr_buf);
|
2391 |
|
2392 |
// Write the address [10:0]
|
2393 |
wr_buf[1] = (address>>8) & 0x07; |
2394 |
wr_buf[0] = address & 0xff; |
2395 |
dwt_writetodevice(OTP_IF_ID, OTP_ADDR, 2, wr_buf);
|
2396 |
|
2397 |
// Enable Sequenced programming
|
2398 |
wr_buf[0] = OTP_CTRL_OTPPROG;
|
2399 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL, 1, wr_buf);
|
2400 |
wr_buf[0] = 0x00; // And clear |
2401 |
dwt_writetodevice(OTP_IF_ID, OTP_CTRL, 1, wr_buf);
|
2402 |
|
2403 |
// WAIT for status to flag PRGM OK..
|
2404 |
otp_done = 0;
|
2405 |
while(otp_done == 0) |
2406 |
{ |
2407 |
deca_sleep(1);
|
2408 |
dwt_readfromdevice(OTP_IF_ID, OTP_STAT, 1, rd_buf);
|
2409 |
|
2410 |
if((rd_buf[0] & 0x01) == 0x01) |
2411 |
{ |
2412 |
otp_done = 1;
|
2413 |
} |
2414 |
} |
2415 |
|
2416 |
return DWT_SUCCESS;
|
2417 |
} |
2418 |
|
2419 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2420 |
* @fn dwt_otpwriteandverify()
|
2421 |
*
|
2422 |
* @brief This is used to program 32-bit value into the DW1000 OTP memory.
|
2423 |
*
|
2424 |
* input parameters
|
2425 |
* @param value - this is the 32-bit value to be programmed into OTP
|
2426 |
* @param address - this is the 16-bit OTP address into which the 32-bit value is programmed
|
2427 |
*
|
2428 |
* output parameters
|
2429 |
*
|
2430 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
2431 |
*/
|
2432 |
int dwt_otpwriteandverify(uint32_t value, uint16_t address)
|
2433 |
{ |
2434 |
int prog_ok = DWT_SUCCESS;
|
2435 |
int retry = 0; |
2436 |
// Firstly set the system clock to crystal
|
2437 |
_dwt_enableclocks(FORCE_SYS_XTI); //set system clock to XTI
|
2438 |
|
2439 |
//
|
2440 |
//!!!!!!!!!!!!!! NOTE !!!!!!!!!!!!!!!!!!!!!
|
2441 |
//Set the supply to 3.7V
|
2442 |
//
|
2443 |
|
2444 |
_dwt_otpsetmrregs(1); // Set mode for programming |
2445 |
|
2446 |
// For each value to program - the readback/check is done couple of times to verify it has programmed successfully
|
2447 |
while(1) |
2448 |
{ |
2449 |
_dwt_otpprogword32(value, address); |
2450 |
|
2451 |
if(_dwt_otpread(address) == value)
|
2452 |
{ |
2453 |
break;
|
2454 |
} |
2455 |
retry++; |
2456 |
if(retry==5) |
2457 |
{ |
2458 |
break;
|
2459 |
} |
2460 |
} |
2461 |
|
2462 |
// Even if the above does not exit before retry reaches 5, the programming has probably been successful
|
2463 |
|
2464 |
_dwt_otpsetmrregs(4); // Set mode for reading |
2465 |
|
2466 |
if(_dwt_otpread(address) != value) // If this does not pass please check voltage supply on VDDIO |
2467 |
{ |
2468 |
prog_ok = DWT_ERROR; |
2469 |
} |
2470 |
|
2471 |
_dwt_otpsetmrregs(0); // Setting OTP mode register for low RM read - resetting the device would be alternative |
2472 |
|
2473 |
return prog_ok;
|
2474 |
} |
2475 |
|
2476 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2477 |
* @fn _dwt_aonconfigupload()
|
2478 |
*
|
2479 |
* @brief This function uploads always on (AON) configuration, as set in the AON_CFG0_OFFSET register.
|
2480 |
*
|
2481 |
* input parameters
|
2482 |
*
|
2483 |
* output parameters
|
2484 |
*
|
2485 |
* no return value
|
2486 |
*/
|
2487 |
void _dwt_aonconfigupload(void) |
2488 |
{ |
2489 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_UPL_CFG); |
2490 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, 0x00); // Clear the register |
2491 |
} |
2492 |
|
2493 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2494 |
* @fn _dwt_aonarrayupload()
|
2495 |
*
|
2496 |
* @brief This function uploads always on (AON) data array and configuration. Thus if this function is used, then _dwt_aonconfigupload
|
2497 |
* is not necessary. The DW1000 will go so SLEEP straight after this if the DWT_SLP_EN has been set.
|
2498 |
*
|
2499 |
* input parameters
|
2500 |
*
|
2501 |
* output parameters
|
2502 |
*
|
2503 |
* no return value
|
2504 |
*/
|
2505 |
void _dwt_aonarrayupload(void) |
2506 |
{ |
2507 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, 0x00); // Clear the register |
2508 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_SAVE); |
2509 |
} |
2510 |
|
2511 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2512 |
* @fn dwt_entersleep()
|
2513 |
*
|
2514 |
* @brief This function puts the device into deep sleep or sleep. dwt_configuresleep() should be called first
|
2515 |
* to configure the sleep and on-wake/wake-up parameters
|
2516 |
*
|
2517 |
* input parameters
|
2518 |
*
|
2519 |
* output parameters
|
2520 |
*
|
2521 |
* no return value
|
2522 |
*/
|
2523 |
void dwt_entersleep(void) |
2524 |
{ |
2525 |
// Copy config to AON - upload the new configuration
|
2526 |
_dwt_aonarrayupload(); |
2527 |
} |
2528 |
|
2529 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2530 |
* @fn dwt_configuresleepcnt()
|
2531 |
*
|
2532 |
* @brief sets the sleep counter to new value, this function programs the high 16-bits of the 28-bit counter
|
2533 |
*
|
2534 |
* NOTE: this function needs to be run before dwt_configuresleep, also the SPI frequency has to be < 3MHz
|
2535 |
*
|
2536 |
* input parameters
|
2537 |
* @param sleepcnt - this it value of the sleep counter to program
|
2538 |
*
|
2539 |
* output parameters
|
2540 |
*
|
2541 |
* no return value
|
2542 |
*/
|
2543 |
void dwt_configuresleepcnt(uint16_t sleepcnt)
|
2544 |
{ |
2545 |
// Force system clock to crystal
|
2546 |
_dwt_enableclocks(FORCE_SYS_XTI); |
2547 |
|
2548 |
// Reset sleep configuration to make sure we don't accidentally go to sleep
|
2549 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG0_OFFSET, 0x00); // NB: this write change the default LPCLKDIVA value which is not used anyway. |
2550 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG1_OFFSET, 0x00);
|
2551 |
|
2552 |
// Disable the sleep counter
|
2553 |
_dwt_aonconfigupload(); |
2554 |
|
2555 |
// Set new value
|
2556 |
dwt_write16bitoffsetreg(AON_ID, AON_CFG0_OFFSET + AON_CFG0_SLEEP_TIM_OFFSET, sleepcnt); |
2557 |
_dwt_aonconfigupload(); |
2558 |
|
2559 |
// Enable the sleep counter
|
2560 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG1_OFFSET, AON_CFG1_SLEEP_CEN); |
2561 |
_dwt_aonconfigupload(); |
2562 |
|
2563 |
// Put system PLL back on
|
2564 |
_dwt_enableclocks(ENABLE_ALL_SEQ); |
2565 |
} |
2566 |
|
2567 |
|
2568 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2569 |
* @fn dwt_calibratesleepcnt()
|
2570 |
*
|
2571 |
* @brief calibrates the local oscillator as its frequency can vary between 7 and 13kHz depending on temp and voltage
|
2572 |
*
|
2573 |
* NOTE: this function needs to be run before dwt_configuresleepcnt, so that we know what the counter units are
|
2574 |
*
|
2575 |
* input parameters
|
2576 |
*
|
2577 |
* output parameters
|
2578 |
*
|
2579 |
* returns the number of XTAL/2 cycles per low-power oscillator cycle. LP OSC frequency = 19.2 MHz/return value
|
2580 |
*/
|
2581 |
uint16_t dwt_calibratesleepcnt(void)
|
2582 |
{ |
2583 |
uint16_t result; |
2584 |
|
2585 |
// Enable calibration of the sleep counter
|
2586 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG1_OFFSET, AON_CFG1_LPOSC_CAL); |
2587 |
_dwt_aonconfigupload(); |
2588 |
|
2589 |
// Disable calibration of the sleep counter
|
2590 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG1_OFFSET, 0x00);
|
2591 |
_dwt_aonconfigupload(); |
2592 |
|
2593 |
// Force system clock to crystal
|
2594 |
_dwt_enableclocks(FORCE_SYS_XTI); |
2595 |
|
2596 |
deca_sleep(1);
|
2597 |
|
2598 |
// Read the number of XTAL/2 cycles one LP oscillator cycle took.
|
2599 |
// Set up address - Read upper byte first
|
2600 |
dwt_write8bitoffsetreg(AON_ID, AON_ADDR_OFFSET, AON_ADDR_LPOSC_CAL_1); |
2601 |
|
2602 |
// Enable manual override
|
2603 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_DCA_ENAB); |
2604 |
|
2605 |
// Read confirm data that was written
|
2606 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_DCA_ENAB | AON_CTRL_DCA_READ); |
2607 |
|
2608 |
// Read back byte from AON
|
2609 |
result = dwt_read8bitoffsetreg(AON_ID, AON_RDAT_OFFSET); |
2610 |
result <<= 8;
|
2611 |
|
2612 |
// Set up address - Read lower byte
|
2613 |
dwt_write8bitoffsetreg(AON_ID, AON_ADDR_OFFSET, AON_ADDR_LPOSC_CAL_0); |
2614 |
|
2615 |
// Enable manual override
|
2616 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_DCA_ENAB); |
2617 |
|
2618 |
// Read confirm data that was written
|
2619 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, AON_CTRL_DCA_ENAB | AON_CTRL_DCA_READ); |
2620 |
|
2621 |
// Read back byte from AON
|
2622 |
result |= dwt_read8bitoffsetreg(AON_ID, AON_RDAT_OFFSET); |
2623 |
|
2624 |
// Disable manual override
|
2625 |
dwt_write8bitoffsetreg(AON_ID, AON_CTRL_OFFSET, 0x00);
|
2626 |
|
2627 |
// Put system PLL back on
|
2628 |
_dwt_enableclocks(ENABLE_ALL_SEQ); |
2629 |
|
2630 |
// Returns the number of XTAL/2 cycles per one LP OSC cycle
|
2631 |
// This can be converted into LP OSC frequency by 19.2 MHz/result
|
2632 |
return result;
|
2633 |
} |
2634 |
|
2635 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2636 |
* @fn dwt_configuresleep()
|
2637 |
*
|
2638 |
* @brief configures the device for both DEEP_SLEEP and SLEEP modes, and on-wake mode
|
2639 |
* i.e. before entering the sleep, the device should be programmed for TX or RX, then upon "waking up" the TX/RX settings
|
2640 |
* will be preserved and the device can immediately perform the desired action TX/RX
|
2641 |
*
|
2642 |
* NOTE: e.g. Tag operation - after deep sleep, the device needs to just load the TX buffer and send the frame
|
2643 |
*
|
2644 |
*
|
2645 |
* mode: the array and LDE code (OTP/ROM) and LDO tune, and set sleep persist
|
2646 |
* DWT_PRESRV_SLEEP 0x0100 - preserve sleep
|
2647 |
* DWT_LOADOPSET 0x0080 - load operating parameter set on wakeup
|
2648 |
* DWT_CONFIG 0x0040 - download the AON array into the HIF (configuration download)
|
2649 |
* DWT_LOADEUI 0x0008
|
2650 |
* DWT_GOTORX 0x0002
|
2651 |
* DWT_TANDV 0x0001
|
2652 |
*
|
2653 |
* wake: wake up parameters
|
2654 |
* DWT_XTAL_EN 0x10 - keep XTAL running during sleep
|
2655 |
* DWT_WAKE_SLPCNT 0x8 - wake up after sleep count
|
2656 |
* DWT_WAKE_CS 0x4 - wake up on chip select
|
2657 |
* DWT_WAKE_WK 0x2 - wake up on WAKEUP PIN
|
2658 |
* DWT_SLP_EN 0x1 - enable sleep/deep sleep functionality
|
2659 |
*
|
2660 |
* input parameters
|
2661 |
* @param mode - config on-wake parameters
|
2662 |
* @param wake - config wake up parameters
|
2663 |
*
|
2664 |
* output parameters
|
2665 |
*
|
2666 |
* no return value
|
2667 |
*/
|
2668 |
void dwt_configuresleep(uint16_t mode, uint8_t wake)
|
2669 |
{ |
2670 |
// Add predefined sleep settings before writing the mode
|
2671 |
mode |= pdw1000local->sleep_mode; |
2672 |
dwt_write16bitoffsetreg(AON_ID, AON_WCFG_OFFSET, mode); |
2673 |
|
2674 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG0_OFFSET, wake); |
2675 |
} |
2676 |
|
2677 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2678 |
* @fn dwt_entersleepaftertx(int enable)
|
2679 |
*
|
2680 |
* @brief sets the auto TX to sleep bit. This means that after a frame
|
2681 |
* transmission the device will enter deep sleep mode. The dwt_configuresleep() function
|
2682 |
* needs to be called before this to configure the on-wake settings
|
2683 |
*
|
2684 |
* NOTE: the IRQ line has to be low/inactive (i.e. no pending events)
|
2685 |
*
|
2686 |
* input parameters
|
2687 |
* @param enable - 1 to configure the device to enter deep sleep after TX, 0 - disables the configuration
|
2688 |
*
|
2689 |
* output parameters
|
2690 |
*
|
2691 |
* no return value
|
2692 |
*/
|
2693 |
void dwt_entersleepaftertx(int enable) |
2694 |
{ |
2695 |
uint32_t reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET); |
2696 |
// Set the auto TX -> sleep bit
|
2697 |
if(enable)
|
2698 |
{ |
2699 |
reg |= PMSC_CTRL1_ATXSLP; |
2700 |
} |
2701 |
else
|
2702 |
{ |
2703 |
reg &= ~(PMSC_CTRL1_ATXSLP); |
2704 |
} |
2705 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, reg); |
2706 |
} |
2707 |
|
2708 |
|
2709 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2710 |
* @fn dwt_spicswakeup()
|
2711 |
*
|
2712 |
* @brief wake up the device from sleep mode using the SPI read,
|
2713 |
* the device will wake up on chip select line going low if the line is held low for at least 500us.
|
2714 |
* To define the length depending on the time one wants to hold
|
2715 |
* the chip select line low, use the following formula:
|
2716 |
*
|
2717 |
* length (bytes) = time (s) * byte_rate (Hz)
|
2718 |
*
|
2719 |
* where fastest byte_rate is spi_rate (Hz) / 8 if the SPI is sending the bytes back-to-back.
|
2720 |
* To save time and power, a system designer could determine byte_rate value more precisely.
|
2721 |
*
|
2722 |
* NOTE: Alternatively the device can be waken up with WAKE_UP pin if configured for that operation
|
2723 |
*
|
2724 |
* input parameters
|
2725 |
* @param buff - this is a pointer to the dummy buffer which will be used in the SPI read transaction used for the WAKE UP of the device
|
2726 |
* @param length - this is the length of the dummy buffer
|
2727 |
*
|
2728 |
* output parameters
|
2729 |
*
|
2730 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error
|
2731 |
*/
|
2732 |
int dwt_spicswakeup(uint8_t *buff, uint16_t length)
|
2733 |
{ |
2734 |
if(dwt_readdevid() != DWT_DEVICE_ID) // Device was in deep sleep (the first read fails) |
2735 |
{ |
2736 |
// Need to keep chip select line low for at least 500us
|
2737 |
dwt_readfromdevice(0x0, 0x0, length, buff); // Do a long read to wake up the chip (hold the chip select low) |
2738 |
|
2739 |
// Need 5ms for XTAL to start and stabilise (could wait for PLL lock IRQ status bit !!!)
|
2740 |
// NOTE: Polling of the STATUS register is not possible unless frequency is < 3MHz
|
2741 |
deca_sleep(5);
|
2742 |
} |
2743 |
else
|
2744 |
{ |
2745 |
return DWT_SUCCESS;
|
2746 |
} |
2747 |
// DEBUG - check if still in sleep mode
|
2748 |
if(dwt_readdevid() != DWT_DEVICE_ID)
|
2749 |
{ |
2750 |
return DWT_ERROR;
|
2751 |
} |
2752 |
|
2753 |
return DWT_SUCCESS;
|
2754 |
} |
2755 |
|
2756 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2757 |
* @fn _dwt_configlde()
|
2758 |
*
|
2759 |
* @brief configure LDE algorithm parameters
|
2760 |
*
|
2761 |
* input parameters
|
2762 |
* @param prf - this is the PRF index (0 or 1) 0 corresponds to 16 and 1 to 64 PRF
|
2763 |
*
|
2764 |
* output parameters
|
2765 |
*
|
2766 |
* no return value
|
2767 |
*/
|
2768 |
void _dwt_configlde(int prfIndex) |
2769 |
{ |
2770 |
dwt_write8bitoffsetreg(LDE_IF_ID, LDE_CFG1_OFFSET, LDE_PARAM1); // 8-bit configuration register
|
2771 |
|
2772 |
if(prfIndex)
|
2773 |
{ |
2774 |
dwt_write16bitoffsetreg( LDE_IF_ID, LDE_CFG2_OFFSET, (uint16_t) LDE_PARAM3_64); // 16-bit LDE configuration tuning register
|
2775 |
} |
2776 |
else
|
2777 |
{ |
2778 |
dwt_write16bitoffsetreg( LDE_IF_ID, LDE_CFG2_OFFSET, (uint16_t) LDE_PARAM3_16); |
2779 |
} |
2780 |
} |
2781 |
|
2782 |
|
2783 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2784 |
* @fn _dwt_loaducodefromrom()
|
2785 |
*
|
2786 |
* @brief load ucode from OTP MEMORY or ROM
|
2787 |
*
|
2788 |
* input parameters
|
2789 |
*
|
2790 |
* output parameters
|
2791 |
*
|
2792 |
* no return value
|
2793 |
*/
|
2794 |
void _dwt_loaducodefromrom(void) |
2795 |
{ |
2796 |
// Set up clocks
|
2797 |
_dwt_enableclocks(FORCE_LDE); |
2798 |
|
2799 |
// Kick off the LDE load
|
2800 |
dwt_write16bitoffsetreg(OTP_IF_ID, OTP_CTRL, OTP_CTRL_LDELOAD); // Set load LDE kick bit
|
2801 |
|
2802 |
deca_sleep(1); // Allow time for code to upload (should take up to 120 us) |
2803 |
|
2804 |
// Default clocks (ENABLE_ALL_SEQ)
|
2805 |
_dwt_enableclocks(ENABLE_ALL_SEQ); // Enable clocks for sequencing
|
2806 |
} |
2807 |
|
2808 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2809 |
* @fn dwt_loadopsettabfromotp()
|
2810 |
*
|
2811 |
* @brief This is used to select which Operational Parameter Set table to load from OTP memory
|
2812 |
*
|
2813 |
* input parameters
|
2814 |
* @param ops_sel - Operational Parameter Set table to load:
|
2815 |
* DWT_OPSET_64LEN = 0x0 - load the operational parameter set table for 64 length preamble configuration
|
2816 |
* DWT_OPSET_TIGHT = 0x1 - load the operational parameter set table for tight xtal offsets (<1ppm)
|
2817 |
* DWT_OPSET_DEFLT = 0x2 - load the default operational parameter set table (this is loaded from reset)
|
2818 |
*
|
2819 |
* output parameters
|
2820 |
*
|
2821 |
* no return value
|
2822 |
*/
|
2823 |
void dwt_loadopsettabfromotp(uint8_t ops_sel)
|
2824 |
{ |
2825 |
uint16_t reg = ((ops_sel << OTP_SF_OPS_SEL_SHFT) & OTP_SF_OPS_SEL_MASK) | OTP_SF_OPS_KICK; // Select defined OPS table and trigger its loading
|
2826 |
|
2827 |
// Set up clocks
|
2828 |
_dwt_enableclocks(FORCE_LDE); |
2829 |
|
2830 |
dwt_write16bitoffsetreg(OTP_IF_ID, OTP_SF, reg); |
2831 |
|
2832 |
// Default clocks (ENABLE_ALL_SEQ)
|
2833 |
_dwt_enableclocks(ENABLE_ALL_SEQ); // Enable clocks for sequencing
|
2834 |
|
2835 |
} |
2836 |
|
2837 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2838 |
* @fn dwt_setsmarttxpower()
|
2839 |
*
|
2840 |
* @brief This call enables or disables the smart TX power feature.
|
2841 |
*
|
2842 |
* input parameters
|
2843 |
* @param enable - this enables or disables the TX smart power (1 = enable, 0 = disable)
|
2844 |
*
|
2845 |
* output parameters
|
2846 |
*
|
2847 |
* no return value
|
2848 |
*/
|
2849 |
void dwt_setsmarttxpower(int enable) |
2850 |
{ |
2851 |
// Config system register
|
2852 |
pdw1000local->sysCFGreg = dwt_read32bitreg(SYS_CFG_ID) ; // Read sysconfig register
|
2853 |
|
2854 |
// Disable smart power configuration
|
2855 |
if(enable)
|
2856 |
{ |
2857 |
pdw1000local->sysCFGreg &= ~(SYS_CFG_DIS_STXP) ; |
2858 |
} |
2859 |
else
|
2860 |
{ |
2861 |
pdw1000local->sysCFGreg |= SYS_CFG_DIS_STXP ; |
2862 |
} |
2863 |
|
2864 |
dwt_write32bitreg(SYS_CFG_ID,pdw1000local->sysCFGreg) ; |
2865 |
} |
2866 |
|
2867 |
|
2868 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2869 |
* @fn dwt_enableautoack()
|
2870 |
*
|
2871 |
* @brief This call enables the auto-ACK feature. If the responseDelayTime (parameter) is 0, the ACK will be sent a.s.a.p.
|
2872 |
* otherwise it will be sent with a programmed delay (in symbols), max is 255.
|
2873 |
* NOTE: needs to have frame filtering enabled as well
|
2874 |
*
|
2875 |
* input parameters
|
2876 |
* @param responseDelayTime - if non-zero the ACK is sent after this delay, max is 255.
|
2877 |
*
|
2878 |
* output parameters
|
2879 |
*
|
2880 |
* no return value
|
2881 |
*/
|
2882 |
void dwt_enableautoack(uint8_t responseDelayTime)
|
2883 |
{ |
2884 |
// Set auto ACK reply delay
|
2885 |
dwt_write8bitoffsetreg(ACK_RESP_T_ID, ACK_RESP_T_ACK_TIM_OFFSET, responseDelayTime); // In symbols
|
2886 |
// Enable auto ACK
|
2887 |
pdw1000local->sysCFGreg |= SYS_CFG_AUTOACK; |
2888 |
dwt_write32bitreg(SYS_CFG_ID,pdw1000local->sysCFGreg) ; |
2889 |
} |
2890 |
|
2891 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2892 |
* @fn dwt_setdblrxbuffmode()
|
2893 |
*
|
2894 |
* @brief This call enables the double receive buffer mode
|
2895 |
*
|
2896 |
* input parameters
|
2897 |
* @param enable - 1 to enable, 0 to disable the double buffer mode
|
2898 |
*
|
2899 |
* output parameters
|
2900 |
*
|
2901 |
* no return value
|
2902 |
*/
|
2903 |
void dwt_setdblrxbuffmode(int enable) |
2904 |
{ |
2905 |
if(enable)
|
2906 |
{ |
2907 |
// Enable double RX buffer mode
|
2908 |
pdw1000local->sysCFGreg &= ~SYS_CFG_DIS_DRXB; |
2909 |
pdw1000local->dblbuffon = 1;
|
2910 |
} |
2911 |
else
|
2912 |
{ |
2913 |
// Disable double RX buffer mode
|
2914 |
pdw1000local->sysCFGreg |= SYS_CFG_DIS_DRXB; |
2915 |
pdw1000local->dblbuffon = 0;
|
2916 |
} |
2917 |
|
2918 |
dwt_write32bitreg(SYS_CFG_ID,pdw1000local->sysCFGreg) ; |
2919 |
} |
2920 |
|
2921 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2922 |
* @fn dwt_setrxaftertxdelay()
|
2923 |
*
|
2924 |
* @brief This sets the receiver turn on delay time after a transmission of a frame
|
2925 |
*
|
2926 |
* input parameters
|
2927 |
* @param rxDelayTime - (20 bits) - the delay is in UWB microseconds
|
2928 |
*
|
2929 |
* output parameters
|
2930 |
*
|
2931 |
* no return value
|
2932 |
*/
|
2933 |
void dwt_setrxaftertxdelay(uint32_t rxDelayTime)
|
2934 |
{ |
2935 |
uint32_t val = dwt_read32bitreg(ACK_RESP_T_ID) ; // Read ACK_RESP_T_ID register
|
2936 |
|
2937 |
val &= ~(ACK_RESP_T_W4R_TIM_MASK) ; // Clear the timer (19:0)
|
2938 |
|
2939 |
val |= (rxDelayTime & ACK_RESP_T_W4R_TIM_MASK) ; // In UWB microseconds (e.g. turn the receiver on 20uus after TX)
|
2940 |
|
2941 |
dwt_write32bitreg(ACK_RESP_T_ID, val) ; |
2942 |
} |
2943 |
|
2944 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2945 |
* @fn dwt_setcallbacks()
|
2946 |
*
|
2947 |
* @brief This function is used to register the different callbacks called when one of the corresponding event occurs.
|
2948 |
*
|
2949 |
* NOTE: Callbacks can be undefined (set to NULL). In this case, dwt_isr() will process the event as usual but the 'null'
|
2950 |
* callback will not be called.
|
2951 |
*
|
2952 |
* input parameters
|
2953 |
* @param cbTxDone - the pointer to the TX confirmation event callback function
|
2954 |
* @param cbRxOk - the pointer to the RX good frame event callback function
|
2955 |
* @param cbRxTo - the pointer to the RX timeout events callback function
|
2956 |
* @param cbRxErr - the pointer to the RX error events callback function
|
2957 |
*
|
2958 |
* output parameters
|
2959 |
*
|
2960 |
* no return value
|
2961 |
*/
|
2962 |
void dwt_setcallbacks(dwt_cb_t cbTxDone, dwt_cb_t cbRxOk, dwt_cb_t cbRxTo, dwt_cb_t cbRxErr)
|
2963 |
{ |
2964 |
pdw1000local->cbTxDone = cbTxDone; |
2965 |
pdw1000local->cbRxOk = cbRxOk; |
2966 |
pdw1000local->cbRxTo = cbRxTo; |
2967 |
pdw1000local->cbRxErr = cbRxErr; |
2968 |
} |
2969 |
|
2970 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2971 |
* @fn dwt_checkirq()
|
2972 |
*
|
2973 |
* @brief This function checks if the IRQ line is active - this is used instead of interrupt handler
|
2974 |
*
|
2975 |
* input parameters
|
2976 |
*
|
2977 |
* output parameters
|
2978 |
*
|
2979 |
* return value is 1 if the IRQS bit is set and 0 otherwise
|
2980 |
*/
|
2981 |
uint8_t dwt_checkirq(void)
|
2982 |
{ |
2983 |
return (dwt_read8bitoffsetreg(SYS_STATUS_ID, SYS_STATUS_OFFSET) & SYS_STATUS_IRQS); // Reading the lower byte only is enough for this operation |
2984 |
} |
2985 |
|
2986 |
/*! ------------------------------------------------------------------------------------------------------------------
|
2987 |
* @fn dwt_isr()
|
2988 |
*
|
2989 |
* @brief This is the DW1000's general Interrupt Service Routine. It will process/report the following events:
|
2990 |
* - RXFCG (through cbRxOk callback)
|
2991 |
* - TXFRS (through cbTxDone callback)
|
2992 |
* - RXRFTO/RXPTO (through cbRxTo callback)
|
2993 |
* - RXPHE/RXFCE/RXRFSL/RXSFDTO/AFFREJ/LDEERR (through cbRxTo cbRxErr)
|
2994 |
* For all events, corresponding interrupts are cleared and necessary resets are performed. In addition, in the RXFCG case,
|
2995 |
* received frame information and frame control are read before calling the callback. If double buffering is activated, it
|
2996 |
* will also toggle between reception buffers once the reception callback processing has ended.
|
2997 |
*
|
2998 |
* /!\ This version of the ISR supports double buffering but does not support automatic RX re-enabling!
|
2999 |
*
|
3000 |
* NOTE: In PC based system using (Cheetah or ARM) USB to SPI converter there can be no interrupts, however we still need something
|
3001 |
* to take the place of it and operate in a polled way. In an embedded system this function should be configured to be triggered
|
3002 |
* on any of the interrupts described above.
|
3003 |
|
3004 |
* input parameters
|
3005 |
*
|
3006 |
* output parameters
|
3007 |
*
|
3008 |
* no return value
|
3009 |
*/
|
3010 |
void dwt_isr(void) |
3011 |
{ |
3012 |
uint32_t status = pdw1000local->cbData.status = dwt_read32bitreg(SYS_STATUS_ID); // Read status register low 32bits
|
3013 |
|
3014 |
// Handle RX good frame event
|
3015 |
if(status & SYS_STATUS_RXFCG)
|
3016 |
{ |
3017 |
uint16_t finfo16; |
3018 |
uint16_t len; |
3019 |
|
3020 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_ALL_RX_GOOD); // Clear all receive status bits
|
3021 |
|
3022 |
pdw1000local->cbData.rx_flags = 0;
|
3023 |
|
3024 |
// Read frame info - Only the first two bytes of the register are used here.
|
3025 |
finfo16 = dwt_read16bitoffsetreg(RX_FINFO_ID, RX_FINFO_OFFSET); |
3026 |
|
3027 |
// Report frame length - Standard frame length up to 127, extended frame length up to 1023 bytes
|
3028 |
len = finfo16 & RX_FINFO_RXFL_MASK_1023; |
3029 |
if(pdw1000local->longFrames == 0) |
3030 |
{ |
3031 |
len &= RX_FINFO_RXFLEN_MASK; |
3032 |
} |
3033 |
pdw1000local->cbData.datalength = len; |
3034 |
|
3035 |
// Report ranging bit
|
3036 |
if(finfo16 & RX_FINFO_RNG)
|
3037 |
{ |
3038 |
pdw1000local->cbData.rx_flags |= DWT_CB_DATA_RX_FLAG_RNG; |
3039 |
} |
3040 |
|
3041 |
// Report frame control - First bytes of the received frame.
|
3042 |
dwt_readfromdevice(RX_BUFFER_ID, 0, FCTRL_LEN_MAX, pdw1000local->cbData.fctrl);
|
3043 |
|
3044 |
// Because of a previous frame not being received properly, AAT bit can be set upon the proper reception of a frame not requesting for
|
3045 |
// acknowledgement (ACK frame is not actually sent though). If the AAT bit is set, check ACK request bit in frame control to confirm (this
|
3046 |
// implementation works only for IEEE802.15.4-2011 compliant frames).
|
3047 |
// This issue is not documented at the time of writing this code. It should be in next release of DW1000 User Manual (v2.09, from July 2016).
|
3048 |
if((status & SYS_STATUS_AAT) && ((pdw1000local->cbData.fctrl[0] & FCTRL_ACK_REQ_MASK) == 0)) |
3049 |
{ |
3050 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_AAT); // Clear AAT status bit in register
|
3051 |
pdw1000local->cbData.status &= ~SYS_STATUS_AAT; // Clear AAT status bit in callback data register copy
|
3052 |
pdw1000local->wait4resp = 0;
|
3053 |
} |
3054 |
|
3055 |
// Call the corresponding callback if present
|
3056 |
if(pdw1000local->cbRxOk != NULL) |
3057 |
{ |
3058 |
pdw1000local->cbRxOk(&pdw1000local->cbData); |
3059 |
} |
3060 |
|
3061 |
if (pdw1000local->dblbuffon)
|
3062 |
{ |
3063 |
// Toggle the Host side Receive Buffer Pointer
|
3064 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_HRBT_OFFSET, 1);
|
3065 |
} |
3066 |
} |
3067 |
|
3068 |
// Handle TX confirmation event
|
3069 |
if(status & SYS_STATUS_TXFRS)
|
3070 |
{ |
3071 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_ALL_TX); // Clear TX event bits
|
3072 |
|
3073 |
// In the case where this TXFRS interrupt is due to the automatic transmission of an ACK solicited by a response (with ACK request bit set)
|
3074 |
// that we receive through using wait4resp to a previous TX (and assuming that the IRQ processing of that TX has already been handled), then
|
3075 |
// we need to handle the IC issue which turns on the RX again in this situation (i.e. because it is wrongly applying the wait4resp after the
|
3076 |
// ACK TX).
|
3077 |
// See section "Transmit and automatically wait for response" in DW1000 User Manual
|
3078 |
if((status & SYS_STATUS_AAT) && pdw1000local->wait4resp)
|
3079 |
{ |
3080 |
dwt_forcetrxoff(); // Turn the RX off
|
3081 |
dwt_rxreset(); // Reset in case we were late and a frame was already being received
|
3082 |
} |
3083 |
|
3084 |
// Call the corresponding callback if present
|
3085 |
if(pdw1000local->cbTxDone != NULL) |
3086 |
{ |
3087 |
pdw1000local->cbTxDone(&pdw1000local->cbData); |
3088 |
} |
3089 |
} |
3090 |
|
3091 |
// Handle frame reception/preamble detect timeout events
|
3092 |
if(status & SYS_STATUS_ALL_RX_TO)
|
3093 |
{ |
3094 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_RXRFTO); // Clear RX timeout event bits
|
3095 |
|
3096 |
pdw1000local->wait4resp = 0;
|
3097 |
|
3098 |
// Because of an issue with receiver restart after error conditions, an RX reset must be applied after any error or timeout event to ensure
|
3099 |
// the next good frame's timestamp is computed correctly.
|
3100 |
// See section "RX Message timestamp" in DW1000 User Manual.
|
3101 |
dwt_forcetrxoff(); |
3102 |
dwt_rxreset(); |
3103 |
|
3104 |
// Call the corresponding callback if present
|
3105 |
if(pdw1000local->cbRxTo != NULL) |
3106 |
{ |
3107 |
pdw1000local->cbRxTo(&pdw1000local->cbData); |
3108 |
} |
3109 |
} |
3110 |
|
3111 |
// Handle RX errors events
|
3112 |
if(status & SYS_STATUS_ALL_RX_ERR)
|
3113 |
{ |
3114 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_ALL_RX_ERR); // Clear RX error event bits
|
3115 |
|
3116 |
pdw1000local->wait4resp = 0;
|
3117 |
|
3118 |
// Because of an issue with receiver restart after error conditions, an RX reset must be applied after any error or timeout event to ensure
|
3119 |
// the next good frame's timestamp is computed correctly.
|
3120 |
// See section "RX Message timestamp" in DW1000 User Manual.
|
3121 |
dwt_forcetrxoff(); |
3122 |
dwt_rxreset(); |
3123 |
|
3124 |
// Call the corresponding callback if present
|
3125 |
if(pdw1000local->cbRxErr != NULL) |
3126 |
{ |
3127 |
pdw1000local->cbRxErr(&pdw1000local->cbData); |
3128 |
} |
3129 |
} |
3130 |
} |
3131 |
|
3132 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3133 |
* @fn dwt_isr_lplisten()
|
3134 |
*
|
3135 |
* @brief This is the DW1000's Interrupt Service Routine to use when low-power listening scheme is implemented. It will
|
3136 |
* only process/report the RXFCG event (through cbRxOk callback).
|
3137 |
* It clears RXFCG interrupt and reads received frame information and frame control before calling the callback.
|
3138 |
*
|
3139 |
* /!\ This version of the ISR is designed for single buffering case only!
|
3140 |
*
|
3141 |
* input parameters
|
3142 |
*
|
3143 |
* output parameters
|
3144 |
*
|
3145 |
* no return value
|
3146 |
*/
|
3147 |
void dwt_lowpowerlistenisr(void) |
3148 |
{ |
3149 |
uint32_t status = pdw1000local->cbData.status = dwt_read32bitreg(SYS_STATUS_ID); // Read status register low 32bits
|
3150 |
uint16_t finfo16; |
3151 |
uint16_t len; |
3152 |
|
3153 |
// The only interrupt handled when in low-power listening mode is RX good frame so proceed directly to the handling of the received frame.
|
3154 |
|
3155 |
// Deactivate low-power listening before clearing the interrupt. If not, the DW1000 will go back to sleep as soon as the interrupt is cleared.
|
3156 |
dwt_setlowpowerlistening(0);
|
3157 |
|
3158 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_ALL_RX_GOOD); // Clear all receive status bits
|
3159 |
|
3160 |
pdw1000local->cbData.rx_flags = 0;
|
3161 |
|
3162 |
// Read frame info - Only the first two bytes of the register are used here.
|
3163 |
finfo16 = dwt_read16bitoffsetreg(RX_FINFO_ID, 0);
|
3164 |
|
3165 |
// Report frame length - Standard frame length up to 127, extended frame length up to 1023 bytes
|
3166 |
len = finfo16 & RX_FINFO_RXFL_MASK_1023; |
3167 |
if(pdw1000local->longFrames == 0) |
3168 |
{ |
3169 |
len &= RX_FINFO_RXFLEN_MASK; |
3170 |
} |
3171 |
pdw1000local->cbData.datalength = len; |
3172 |
|
3173 |
// Report ranging bit
|
3174 |
if(finfo16 & RX_FINFO_RNG)
|
3175 |
{ |
3176 |
pdw1000local->cbData.rx_flags |= DWT_CB_DATA_RX_FLAG_RNG; |
3177 |
} |
3178 |
|
3179 |
// Report frame control - First bytes of the received frame.
|
3180 |
dwt_readfromdevice(RX_BUFFER_ID, 0, FCTRL_LEN_MAX, pdw1000local->cbData.fctrl);
|
3181 |
|
3182 |
// Because of a previous frame not being received properly, AAT bit can be set upon the proper reception of a frame not requesting for
|
3183 |
// acknowledgement (ACK frame is not actually sent though). If the AAT bit is set, check ACK request bit in frame control to confirm (this
|
3184 |
// implementation works only for IEEE802.15.4-2011 compliant frames).
|
3185 |
// This issue is not documented at the time of writing this code. It should be in next release of DW1000 User Manual (v2.09, from July 2016).
|
3186 |
if((status & SYS_STATUS_AAT) && ((pdw1000local->cbData.fctrl[0] & FCTRL_ACK_REQ_MASK) == 0)) |
3187 |
{ |
3188 |
dwt_write32bitreg(SYS_STATUS_ID, SYS_STATUS_AAT); // Clear AAT status bit in register
|
3189 |
pdw1000local->cbData.status &= ~SYS_STATUS_AAT; // Clear AAT status bit in callback data register copy
|
3190 |
pdw1000local->wait4resp = 0;
|
3191 |
} |
3192 |
|
3193 |
// Call the corresponding callback if present
|
3194 |
if(pdw1000local->cbRxOk != NULL) |
3195 |
{ |
3196 |
pdw1000local->cbRxOk(&pdw1000local->cbData); |
3197 |
} |
3198 |
} |
3199 |
|
3200 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3201 |
* @fn dwt_setleds()
|
3202 |
*
|
3203 |
* @brief This is used to set up Tx/Rx GPIOs which could be used to control LEDs
|
3204 |
* Note: not completely IC dependent, also needs board with LEDS fitted on right I/O lines
|
3205 |
* this function enables GPIOs 2 and 3 which are connected to LED3 and LED4 on EVB1000
|
3206 |
*
|
3207 |
* input parameters
|
3208 |
* @param mode - this is a bit field interpreted as follows:
|
3209 |
* - bit 0: 1 to enable LEDs, 0 to disable them
|
3210 |
* - bit 1: 1 to make LEDs blink once on init. Only valid if bit 0 is set (enable LEDs)
|
3211 |
* - bit 2 to 7: reserved
|
3212 |
*
|
3213 |
* output parameters none
|
3214 |
*
|
3215 |
* no return value
|
3216 |
*/
|
3217 |
void dwt_setleds(uint8_t mode)
|
3218 |
{ |
3219 |
uint32_t reg; |
3220 |
|
3221 |
if (mode & DWT_LEDS_ENABLE)
|
3222 |
{ |
3223 |
// Set up MFIO for LED output.
|
3224 |
reg = dwt_read32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET); |
3225 |
reg &= ~(GPIO_MSGP2_MASK | GPIO_MSGP3_MASK); |
3226 |
reg |= (GPIO_PIN2_RXLED | GPIO_PIN3_TXLED); |
3227 |
dwt_write32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET, reg); |
3228 |
|
3229 |
// Enable LP Oscillator to run from counter and turn on de-bounce clock.
|
3230 |
reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET); |
3231 |
reg |= (PMSC_CTRL0_GPDCE | PMSC_CTRL0_KHZCLEN); |
3232 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, reg); |
3233 |
|
3234 |
// Enable LEDs to blink and set default blink time.
|
3235 |
reg = PMSC_LEDC_BLNKEN | PMSC_LEDC_BLINK_TIME_DEF; |
3236 |
// Make LEDs blink once if requested.
|
3237 |
if (mode & DWT_LEDS_INIT_BLINK)
|
3238 |
{ |
3239 |
reg |= PMSC_LEDC_BLINK_NOW_ALL; |
3240 |
} |
3241 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_LEDC_OFFSET, reg); |
3242 |
// Clear force blink bits if needed.
|
3243 |
if(mode & DWT_LEDS_INIT_BLINK)
|
3244 |
{ |
3245 |
reg &= ~PMSC_LEDC_BLINK_NOW_ALL; |
3246 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_LEDC_OFFSET, reg); |
3247 |
} |
3248 |
} |
3249 |
else
|
3250 |
{ |
3251 |
// Clear the GPIO bits that are used for LED control.
|
3252 |
reg = dwt_read32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET); |
3253 |
reg &= ~(GPIO_MSGP2_MASK | GPIO_MSGP3_MASK); |
3254 |
dwt_write32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET, reg); |
3255 |
} |
3256 |
} |
3257 |
|
3258 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3259 |
* @fn _dwt_enableclocks()
|
3260 |
*
|
3261 |
* @brief function to enable/disable clocks to particular digital blocks/system
|
3262 |
*
|
3263 |
* input parameters
|
3264 |
* @param clocks - set of clocks to enable/disable
|
3265 |
*
|
3266 |
* output parameters none
|
3267 |
*
|
3268 |
* no return value
|
3269 |
*/
|
3270 |
void _dwt_enableclocks(int clocks) |
3271 |
{ |
3272 |
uint8_t reg[2];
|
3273 |
|
3274 |
dwt_readfromdevice(PMSC_ID, PMSC_CTRL0_OFFSET, 2, reg);
|
3275 |
switch(clocks)
|
3276 |
{ |
3277 |
case ENABLE_ALL_SEQ:
|
3278 |
{ |
3279 |
reg[0] = 0x00 ; |
3280 |
reg[1] = reg[1] & 0xfe; |
3281 |
} |
3282 |
break;
|
3283 |
case FORCE_SYS_XTI:
|
3284 |
{ |
3285 |
// System and RX
|
3286 |
reg[0] = 0x01 | (reg[0] & 0xfc); |
3287 |
} |
3288 |
break;
|
3289 |
case FORCE_SYS_PLL:
|
3290 |
{ |
3291 |
// System
|
3292 |
reg[0] = 0x02 | (reg[0] & 0xfc); |
3293 |
} |
3294 |
break;
|
3295 |
case READ_ACC_ON:
|
3296 |
{ |
3297 |
reg[0] = 0x48 | (reg[0] & 0xb3); |
3298 |
reg[1] = 0x80 | reg[1]; |
3299 |
} |
3300 |
break;
|
3301 |
case READ_ACC_OFF:
|
3302 |
{ |
3303 |
reg[0] = reg[0] & 0xb3; |
3304 |
reg[1] = 0x7f & reg[1]; |
3305 |
} |
3306 |
break;
|
3307 |
case FORCE_OTP_ON:
|
3308 |
{ |
3309 |
reg[1] = 0x02 | reg[1]; |
3310 |
} |
3311 |
break;
|
3312 |
case FORCE_OTP_OFF:
|
3313 |
{ |
3314 |
reg[1] = reg[1] & 0xfd; |
3315 |
} |
3316 |
break;
|
3317 |
case FORCE_TX_PLL:
|
3318 |
{ |
3319 |
reg[0] = 0x20 | (reg[0] & 0xcf); |
3320 |
} |
3321 |
break;
|
3322 |
case FORCE_LDE:
|
3323 |
{ |
3324 |
reg[0] = 0x01; |
3325 |
reg[1] = 0x03; |
3326 |
} |
3327 |
break;
|
3328 |
default:
|
3329 |
break;
|
3330 |
} |
3331 |
|
3332 |
|
3333 |
// Need to write lower byte separately before setting the higher byte(s)
|
3334 |
dwt_writetodevice(PMSC_ID, PMSC_CTRL0_OFFSET, 1, ®[0]); |
3335 |
dwt_writetodevice(PMSC_ID, 0x1, 1, ®[1]); |
3336 |
|
3337 |
} // end _dwt_enableclocks()
|
3338 |
|
3339 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3340 |
* @fn _dwt_disablesequencing()
|
3341 |
*
|
3342 |
* @brief This function disables the TX blocks sequencing, it disables PMSC control of RF blocks, system clock is also set to XTAL
|
3343 |
*
|
3344 |
* input parameters none
|
3345 |
*
|
3346 |
* output parameters none
|
3347 |
*
|
3348 |
* no return value
|
3349 |
*/
|
3350 |
void _dwt_disablesequencing(void) // Disable sequencing and go to state "INIT" |
3351 |
{ |
3352 |
_dwt_enableclocks(FORCE_SYS_XTI); // Set system clock to XTI
|
3353 |
|
3354 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, PMSC_CTRL1_PKTSEQ_DISABLE); // Disable PMSC ctrl of RF and RX clk blocks
|
3355 |
} |
3356 |
|
3357 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3358 |
* @fn dwt_setdelayedtrxtime()
|
3359 |
*
|
3360 |
* @brief This API function configures the delayed transmit time or the delayed RX on time
|
3361 |
*
|
3362 |
* input parameters
|
3363 |
* @param starttime - the TX/RX start time (the 32 bits should be the high 32 bits of the system time at which to send the message,
|
3364 |
* or at which to turn on the receiver)
|
3365 |
*
|
3366 |
* output parameters none
|
3367 |
*
|
3368 |
* no return value
|
3369 |
*/
|
3370 |
void dwt_setdelayedtrxtime(uint32_t starttime)
|
3371 |
{ |
3372 |
dwt_write32bitoffsetreg(DX_TIME_ID, 1, starttime); // Write at offset 1 as the lower 9 bits of this register are ignored |
3373 |
|
3374 |
} // end dwt_setdelayedtrxtime()
|
3375 |
|
3376 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3377 |
* @fn dwt_starttx()
|
3378 |
*
|
3379 |
* @brief This call initiates the transmission, input parameter indicates which TX mode is used see below
|
3380 |
*
|
3381 |
* input parameters:
|
3382 |
* @param mode - if 0 immediate TX (no response expected)
|
3383 |
* if 1 delayed TX (no response expected)
|
3384 |
* if 2 immediate TX (response expected - so the receiver will be automatically turned on after TX is done)
|
3385 |
* if 3 delayed TX (response expected - so the receiver will be automatically turned on after TX is done)
|
3386 |
*
|
3387 |
* output parameters
|
3388 |
*
|
3389 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error (e.g. a delayed transmission will fail if the delayed time has passed)
|
3390 |
*/
|
3391 |
int dwt_starttx(uint8_t mode)
|
3392 |
{ |
3393 |
int retval = DWT_SUCCESS ;
|
3394 |
uint8_t temp = 0x00;
|
3395 |
uint16_t checkTxOK = 0 ;
|
3396 |
|
3397 |
if(mode & DWT_RESPONSE_EXPECTED)
|
3398 |
{ |
3399 |
temp = (uint8_t)SYS_CTRL_WAIT4RESP ; // Set wait4response bit
|
3400 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, temp); |
3401 |
pdw1000local->wait4resp = 1;
|
3402 |
} |
3403 |
|
3404 |
if (mode & DWT_START_TX_DELAYED)
|
3405 |
{ |
3406 |
// Both SYS_CTRL_TXSTRT and SYS_CTRL_TXDLYS to correctly enable TX
|
3407 |
temp |= (uint8_t)(SYS_CTRL_TXDLYS | SYS_CTRL_TXSTRT) ; |
3408 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, temp); |
3409 |
checkTxOK = dwt_read16bitoffsetreg(SYS_STATUS_ID, 3); // Read at offset 3 to get the upper 2 bytes out of 5 |
3410 |
if ((checkTxOK & SYS_STATUS_TXERR) == 0) // Transmit Delayed Send set over Half a Period away or Power Up error (there is enough time to send but not to power up individual blocks). |
3411 |
{ |
3412 |
retval = DWT_SUCCESS ; // All okay
|
3413 |
} |
3414 |
else
|
3415 |
{ |
3416 |
// I am taking DSHP set to Indicate that the TXDLYS was set too late for the specified DX_TIME.
|
3417 |
// Remedial Action - (a) cancel delayed send
|
3418 |
temp = (uint8_t)SYS_CTRL_TRXOFF; // This assumes the bit is in the lowest byte
|
3419 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, temp); |
3420 |
// Note event Delayed TX Time too Late
|
3421 |
// Could fall through to start a normal send (below) just sending late.....
|
3422 |
// ... instead return and assume return value of 1 will be used to detect and recover from the issue.
|
3423 |
pdw1000local->wait4resp = 0;
|
3424 |
retval = DWT_ERROR ; // Failed !
|
3425 |
} |
3426 |
} |
3427 |
else
|
3428 |
{ |
3429 |
temp |= (uint8_t)SYS_CTRL_TXSTRT ; |
3430 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, temp); |
3431 |
} |
3432 |
|
3433 |
return retval;
|
3434 |
|
3435 |
} // end dwt_starttx()
|
3436 |
|
3437 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3438 |
* @fn dwt_forcetrxoff()
|
3439 |
*
|
3440 |
* @brief This is used to turn off the transceiver
|
3441 |
*
|
3442 |
* input parameters
|
3443 |
*
|
3444 |
* output parameters
|
3445 |
*
|
3446 |
* no return value
|
3447 |
*/
|
3448 |
void dwt_forcetrxoff(void) |
3449 |
{ |
3450 |
decaIrqStatus_t stat ; |
3451 |
uint32_t mask; |
3452 |
|
3453 |
mask = dwt_read32bitreg(SYS_MASK_ID) ; // Read set interrupt mask
|
3454 |
|
3455 |
// Need to beware of interrupts occurring in the middle of following read modify write cycle
|
3456 |
// We can disable the radio, but before the status is cleared an interrupt can be set (e.g. the
|
3457 |
// event has just happened before the radio was disabled)
|
3458 |
// thus we need to disable interrupt during this operation
|
3459 |
stat = decamutexon() ; |
3460 |
|
3461 |
dwt_write32bitreg(SYS_MASK_ID, 0) ; // Clear interrupt mask - so we don't get any unwanted events |
3462 |
|
3463 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, (uint8_t)SYS_CTRL_TRXOFF) ; // Disable the radio
|
3464 |
|
3465 |
// Forcing Transceiver off - so we do not want to see any new events that may have happened
|
3466 |
dwt_write32bitreg(SYS_STATUS_ID, (SYS_STATUS_ALL_TX | SYS_STATUS_ALL_RX_ERR | SYS_STATUS_ALL_RX_TO | SYS_STATUS_ALL_RX_GOOD)); |
3467 |
|
3468 |
dwt_syncrxbufptrs(); |
3469 |
|
3470 |
dwt_write32bitreg(SYS_MASK_ID, mask) ; // Set interrupt mask to what it was
|
3471 |
|
3472 |
// Enable/restore interrupts again...
|
3473 |
decamutexoff(stat) ; |
3474 |
pdw1000local->wait4resp = 0;
|
3475 |
|
3476 |
} // end deviceforcetrxoff()
|
3477 |
|
3478 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3479 |
* @fn dwt_syncrxbufptrs()
|
3480 |
*
|
3481 |
* @brief this function synchronizes rx buffer pointers
|
3482 |
* need to make sure that the host/IC buffer pointers are aligned before starting RX
|
3483 |
*
|
3484 |
* input parameters:
|
3485 |
*
|
3486 |
* output parameters
|
3487 |
*
|
3488 |
* no return value
|
3489 |
*/
|
3490 |
void dwt_syncrxbufptrs(void) |
3491 |
{ |
3492 |
uint8_t buff ; |
3493 |
// Need to make sure that the host/IC buffer pointers are aligned before starting RX
|
3494 |
buff = dwt_read8bitoffsetreg(SYS_STATUS_ID, 3); // Read 1 byte at offset 3 to get the 4th byte out of 5 |
3495 |
|
3496 |
if((buff & (SYS_STATUS_ICRBP >> 24)) != // IC side Receive Buffer Pointer |
3497 |
((buff & (SYS_STATUS_HSRBP>>24)) << 1) ) // Host Side Receive Buffer Pointer |
3498 |
{ |
3499 |
dwt_write8bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_HRBT_OFFSET , 0x01) ; // We need to swap RX buffer status reg (write one to toggle internally) |
3500 |
} |
3501 |
} |
3502 |
|
3503 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3504 |
* @fn dwt_setsniffmode()
|
3505 |
*
|
3506 |
* @brief enable/disable and configure SNIFF mode.
|
3507 |
*
|
3508 |
* SNIFF mode is a low-power reception mode where the receiver is sequenced on and off instead of being on all the time.
|
3509 |
* The time spent in each state (on/off) is specified through the parameters below.
|
3510 |
* See DW1000 User Manual section 4.5 "Low-Power SNIFF mode" for more details.
|
3511 |
*
|
3512 |
* input parameters:
|
3513 |
* @param enable - 1 to enable SNIFF mode, 0 to disable. When 0, all other parameters are not taken into account.
|
3514 |
* @param timeOn - duration of receiver ON phase, expressed in multiples of PAC size. The counter automatically adds 1 PAC
|
3515 |
* size to the value set. Min value that can be set is 1 (i.e. an ON time of 2 PAC size), max value is 15.
|
3516 |
* @param timeOff - duration of receiver OFF phase, expressed in multiples of 128/125 µs (~1 µs). Max value is 255.
|
3517 |
*
|
3518 |
* output parameters
|
3519 |
*
|
3520 |
* no return value
|
3521 |
*/
|
3522 |
void dwt_setsniffmode(int enable, uint8_t timeOn, uint8_t timeOff) |
3523 |
{ |
3524 |
uint32_t pmsc_reg; |
3525 |
if (enable)
|
3526 |
{ |
3527 |
/* Configure ON/OFF times and enable PLL2 on/off sequencing by SNIFF mode. */
|
3528 |
uint16_t sniff_reg = (uint16_t)((timeOff << 8) | timeOn) & RX_SNIFF_MASK;
|
3529 |
dwt_write16bitoffsetreg(RX_SNIFF_ID, RX_SNIFF_OFFSET, sniff_reg); |
3530 |
pmsc_reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET); |
3531 |
pmsc_reg |= PMSC_CTRL0_PLL2_SEQ_EN; |
3532 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, pmsc_reg); |
3533 |
} |
3534 |
else
|
3535 |
{ |
3536 |
/* Clear ON/OFF times and disable PLL2 on/off sequencing by SNIFF mode. */
|
3537 |
dwt_write16bitoffsetreg(RX_SNIFF_ID, RX_SNIFF_OFFSET, 0x0000);
|
3538 |
pmsc_reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET); |
3539 |
pmsc_reg &= ~PMSC_CTRL0_PLL2_SEQ_EN; |
3540 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, pmsc_reg); |
3541 |
} |
3542 |
} |
3543 |
|
3544 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3545 |
* @fn dwt_setlowpowerlistening()
|
3546 |
*
|
3547 |
* @brief enable/disable low-power listening mode.
|
3548 |
*
|
3549 |
* Low-power listening is a feature whereby the DW1000 is predominantly in the SLEEP state but wakes periodically, (after
|
3550 |
* this "long sleep"), for a very short time to sample the air for a preamble sequence. This preamble sampling "listening"
|
3551 |
* phase is actually two reception phases separated by a "short sleep" time. See DW1000 User Manual section "Low-Power
|
3552 |
* Listening" for more details.
|
3553 |
*
|
3554 |
* NOTE: Before enabling low-power listening, the following functions have to be called to fully configure it:
|
3555 |
* - dwt_configuresleep() to configure long sleep phase. "mode" parameter should at least have DWT_PRESRV_SLEEP,
|
3556 |
* DWT_CONFIG and DWT_RX_EN set and "wake" parameter should at least have both DWT_WAKE_SLPCNT and DWT_SLP_EN set.
|
3557 |
* - dwt_calibratesleepcnt() and dwt_configuresleepcnt() to define the "long sleep" phase duration.
|
3558 |
* - dwt_setsnoozetime() to define the "short sleep" phase duration.
|
3559 |
* - dwt_setpreambledetecttimeout() to define the reception phases duration.
|
3560 |
* - dwt_setinterrupt() to activate RX good frame interrupt (DWT_INT_RFCG) only.
|
3561 |
* When configured, low-power listening mode can be triggered either by putting the DW1000 to sleep (using
|
3562 |
* dwt_entersleep()) or by activating reception (using dwt_rxenable()).
|
3563 |
*
|
3564 |
* Please refer to the low-power listening examples (examples 8a/8b accompanying the API distribution on Decawave's
|
3565 |
* website). They form a working example code that shows how to use low-power listening correctly.
|
3566 |
*
|
3567 |
* input parameters:
|
3568 |
* @param enable - 1 to enable low-power listening, 0 to disable.
|
3569 |
*
|
3570 |
* output parameters
|
3571 |
*
|
3572 |
* no return value
|
3573 |
*/
|
3574 |
void dwt_setlowpowerlistening(int enable) |
3575 |
{ |
3576 |
uint32_t pmsc_reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET); |
3577 |
if (enable)
|
3578 |
{ |
3579 |
/* Configure RX to sleep and snooze features. */
|
3580 |
pmsc_reg |= (PMSC_CTRL1_ARXSLP | PMSC_CTRL1_SNOZE); |
3581 |
} |
3582 |
else
|
3583 |
{ |
3584 |
/* Reset RX to sleep and snooze features. */
|
3585 |
pmsc_reg &= ~(PMSC_CTRL1_ARXSLP | PMSC_CTRL1_SNOZE); |
3586 |
} |
3587 |
dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, pmsc_reg); |
3588 |
} |
3589 |
|
3590 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3591 |
* @fn dwt_setsnoozetime()
|
3592 |
*
|
3593 |
* @brief Set duration of "short sleep" phase when in low-power listening mode.
|
3594 |
*
|
3595 |
* input parameters:
|
3596 |
* @param snooze_time - "short sleep" phase duration, expressed in multiples of 512/19.2 µs (~26.7 µs). The counter
|
3597 |
* automatically adds 1 to the value set. The smallest working value that should be set is 1,
|
3598 |
* i.e. giving a snooze time of 2 units (or ~53 µs).
|
3599 |
*
|
3600 |
* output parameters
|
3601 |
*
|
3602 |
* no return value
|
3603 |
*/
|
3604 |
void dwt_setsnoozetime(uint8_t snooze_time)
|
3605 |
{ |
3606 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_SNOZT_OFFSET, snooze_time); |
3607 |
} |
3608 |
|
3609 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3610 |
* @fn dwt_rxenable()
|
3611 |
*
|
3612 |
* @brief This call turns on the receiver, can be immediate or delayed (depending on the mode parameter). In the case of a
|
3613 |
* "late" error the receiver will only be turned on if the DWT_IDLE_ON_DLY_ERR is not set.
|
3614 |
* The receiver will stay turned on, listening to any messages until
|
3615 |
* it either receives a good frame, an error (CRC, PHY header, Reed Solomon) or it times out (SFD, Preamble or Frame).
|
3616 |
*
|
3617 |
* input parameters
|
3618 |
* @param mode - this can be one of the following allowed values:
|
3619 |
*
|
3620 |
* DWT_START_RX_IMMEDIATE 0 used to enbale receiver immediately
|
3621 |
* DWT_START_RX_DELAYED 1 used to set up delayed RX, if "late" error triggers, then the RX will be enabled immediately
|
3622 |
* (DWT_START_RX_DELAYED | DWT_IDLE_ON_DLY_ERR) 3 used to disable re-enabling of receiver if delayed RX failed due to "late" error
|
3623 |
* (DWT_START_RX_IMMEDIATE | DWT_NO_SYNC_PTRS) 4 used to re-enable RX without trying to sync IC and host side buffer pointers, typically when
|
3624 |
* performing manual RX re-enabling in double buffering mode
|
3625 |
*
|
3626 |
* returns DWT_SUCCESS for success, or DWT_ERROR for error (e.g. a delayed receive enable will be too far in the future if delayed time has passed)
|
3627 |
*/
|
3628 |
int dwt_rxenable(int mode) |
3629 |
{ |
3630 |
uint16_t temp ; |
3631 |
uint8_t temp1 ; |
3632 |
|
3633 |
if ((mode & DWT_NO_SYNC_PTRS) == 0) |
3634 |
{ |
3635 |
dwt_syncrxbufptrs(); |
3636 |
} |
3637 |
|
3638 |
temp = (uint16_t)SYS_CTRL_RXENAB ; |
3639 |
|
3640 |
if (mode & DWT_START_RX_DELAYED)
|
3641 |
{ |
3642 |
temp |= (uint16_t)SYS_CTRL_RXDLYE ; |
3643 |
} |
3644 |
|
3645 |
dwt_write16bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, temp); |
3646 |
|
3647 |
if (mode & DWT_START_RX_DELAYED) // check for errors |
3648 |
{ |
3649 |
temp1 = dwt_read8bitoffsetreg(SYS_STATUS_ID, 3); // Read 1 byte at offset 3 to get the 4th byte out of 5 |
3650 |
if ((temp1 & (SYS_STATUS_HPDWARN >> 24)) != 0) // if delay has passed do immediate RX on unless DWT_IDLE_ON_DLY_ERR is true |
3651 |
{ |
3652 |
dwt_forcetrxoff(); // turn the delayed receive off
|
3653 |
|
3654 |
if((mode & DWT_IDLE_ON_DLY_ERR) == 0) // if DWT_IDLE_ON_DLY_ERR not set then re-enable receiver |
3655 |
{ |
3656 |
dwt_write16bitoffsetreg(SYS_CTRL_ID, SYS_CTRL_OFFSET, SYS_CTRL_RXENAB); |
3657 |
} |
3658 |
return DWT_ERROR; // return warning indication |
3659 |
} |
3660 |
} |
3661 |
|
3662 |
return DWT_SUCCESS;
|
3663 |
} // end dwt_rxenable()
|
3664 |
|
3665 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3666 |
* @fn dwt_setrxtimeout()
|
3667 |
*
|
3668 |
* @brief This call enables RX timeout (SY_STAT_RFTO event)
|
3669 |
*
|
3670 |
* input parameters
|
3671 |
* @param time - how long the receiver remains on from the RX enable command
|
3672 |
* The time parameter used here is in 1.0256 us (512/499.2MHz) units
|
3673 |
* If set to 0 the timeout is disabled.
|
3674 |
*
|
3675 |
* output parameters
|
3676 |
*
|
3677 |
* no return value
|
3678 |
*/
|
3679 |
void dwt_setrxtimeout(uint16_t time)
|
3680 |
{ |
3681 |
uint8_t temp ; |
3682 |
|
3683 |
temp = dwt_read8bitoffsetreg(SYS_CFG_ID, 3); // Read at offset 3 to get the upper byte only |
3684 |
|
3685 |
if(time > 0) |
3686 |
{ |
3687 |
dwt_write16bitoffsetreg(RX_FWTO_ID, RX_FWTO_OFFSET, time) ; |
3688 |
|
3689 |
temp |= (uint8_t)(SYS_CFG_RXWTOE>>24); // Shift RXWTOE mask as we read the upper byte only |
3690 |
// OR in 32bit value (1 bit set), I know this is in high byte.
|
3691 |
pdw1000local->sysCFGreg |= SYS_CFG_RXWTOE; |
3692 |
|
3693 |
dwt_write8bitoffsetreg(SYS_CFG_ID, 3, temp); // Write at offset 3 to write the upper byte only |
3694 |
} |
3695 |
else
|
3696 |
{ |
3697 |
temp &= ~((uint8_t)(SYS_CFG_RXWTOE>>24)); // Shift RXWTOE mask as we read the upper byte only |
3698 |
// AND in inverted 32bit value (1 bit clear), I know this is in high byte.
|
3699 |
pdw1000local->sysCFGreg &= ~(SYS_CFG_RXWTOE); |
3700 |
|
3701 |
dwt_write8bitoffsetreg(SYS_CFG_ID, 3, temp); // Write at offset 3 to write the upper byte only |
3702 |
} |
3703 |
|
3704 |
} // end dwt_setrxtimeout()
|
3705 |
|
3706 |
|
3707 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3708 |
* @fn dwt_setpreambledetecttimeout()
|
3709 |
*
|
3710 |
* @brief This call enables preamble timeout (SY_STAT_RXPTO event)
|
3711 |
*
|
3712 |
* input parameters
|
3713 |
* @param timeout - Preamble detection timeout, expressed in multiples of PAC size. The counter automatically adds 1 PAC
|
3714 |
* size to the value set. Min value that can be set is 1 (i.e. a timeout of 2 PAC size).
|
3715 |
*
|
3716 |
* output parameters
|
3717 |
*
|
3718 |
* no return value
|
3719 |
*/
|
3720 |
void dwt_setpreambledetecttimeout(uint16_t timeout)
|
3721 |
{ |
3722 |
dwt_write16bitoffsetreg(DRX_CONF_ID, DRX_PRETOC_OFFSET, timeout); |
3723 |
} |
3724 |
|
3725 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3726 |
* @fn void dwt_setinterrupt()
|
3727 |
*
|
3728 |
* @brief This function enables the specified events to trigger an interrupt.
|
3729 |
* The following events can be enabled:
|
3730 |
* DWT_INT_TFRS 0x00000080 // frame sent
|
3731 |
* DWT_INT_RFCG 0x00004000 // frame received with good CRC
|
3732 |
* DWT_INT_RPHE 0x00001000 // receiver PHY header error
|
3733 |
* DWT_INT_RFCE 0x00008000 // receiver CRC error
|
3734 |
* DWT_INT_RFSL 0x00010000 // receiver sync loss error
|
3735 |
* DWT_INT_RFTO 0x00020000 // frame wait timeout
|
3736 |
* DWT_INT_RXPTO 0x00200000 // preamble detect timeout
|
3737 |
* DWT_INT_SFDT 0x04000000 // SFD timeout
|
3738 |
* DWT_INT_ARFE 0x20000000 // frame rejected (due to frame filtering configuration)
|
3739 |
*
|
3740 |
*
|
3741 |
* input parameters:
|
3742 |
* @param bitmask - sets the events which will generate interrupt
|
3743 |
* @param enable - if set the interrupts are enabled else they are cleared
|
3744 |
*
|
3745 |
* output parameters
|
3746 |
*
|
3747 |
* no return value
|
3748 |
*/
|
3749 |
void dwt_setinterrupt(uint32_t bitmask, uint8_t enable)
|
3750 |
{ |
3751 |
decaIrqStatus_t stat ; |
3752 |
uint32_t mask ; |
3753 |
|
3754 |
// Need to beware of interrupts occurring in the middle of following read modify write cycle
|
3755 |
stat = decamutexon() ; |
3756 |
|
3757 |
mask = dwt_read32bitreg(SYS_MASK_ID) ; // Read register
|
3758 |
|
3759 |
if(enable)
|
3760 |
{ |
3761 |
mask |= bitmask ; |
3762 |
} |
3763 |
else
|
3764 |
{ |
3765 |
mask &= ~bitmask ; // Clear the bit
|
3766 |
} |
3767 |
dwt_write32bitreg(SYS_MASK_ID,mask) ; // New value
|
3768 |
|
3769 |
decamutexoff(stat) ; |
3770 |
} |
3771 |
|
3772 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3773 |
* @fn dwt_configeventcounters()
|
3774 |
*
|
3775 |
* @brief This is used to enable/disable the event counter in the IC
|
3776 |
*
|
3777 |
* input parameters
|
3778 |
* @param - enable - 1 enables (and reset), 0 disables the event counters
|
3779 |
* output parameters
|
3780 |
*
|
3781 |
* no return value
|
3782 |
*/
|
3783 |
void dwt_configeventcounters(int enable) |
3784 |
{ |
3785 |
// Need to clear and disable, can't just clear
|
3786 |
dwt_write8bitoffsetreg(DIG_DIAG_ID, EVC_CTRL_OFFSET, (uint8_t)(EVC_CLR)); |
3787 |
|
3788 |
if(enable)
|
3789 |
{ |
3790 |
dwt_write8bitoffsetreg(DIG_DIAG_ID, EVC_CTRL_OFFSET, (uint8_t)(EVC_EN)); // Enable
|
3791 |
} |
3792 |
} |
3793 |
|
3794 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3795 |
* @fn dwt_readeventcounters()
|
3796 |
*
|
3797 |
* @brief This is used to read the event counters in the IC
|
3798 |
*
|
3799 |
* input parameters
|
3800 |
* @param counters - pointer to the dwt_deviceentcnts_t structure which will hold the read data
|
3801 |
*
|
3802 |
* output parameters
|
3803 |
*
|
3804 |
* no return value
|
3805 |
*/
|
3806 |
void dwt_readeventcounters(dwt_deviceentcnts_t *counters)
|
3807 |
{ |
3808 |
uint32_t temp; |
3809 |
|
3810 |
temp= dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_PHE_OFFSET); // Read sync loss (31-16), PHE (15-0)
|
3811 |
counters->PHE = temp & 0xFFF;
|
3812 |
counters->RSL = (temp >> 16) & 0xFFF; |
3813 |
|
3814 |
temp = dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_FCG_OFFSET); // Read CRC bad (31-16), CRC good (15-0)
|
3815 |
counters->CRCG = temp & 0xFFF;
|
3816 |
counters->CRCB = (temp >> 16) & 0xFFF; |
3817 |
|
3818 |
temp = dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_FFR_OFFSET); // Overruns (31-16), address errors (15-0)
|
3819 |
counters->ARFE = temp & 0xFFF;
|
3820 |
counters->OVER = (temp >> 16) & 0xFFF; |
3821 |
|
3822 |
temp = dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_STO_OFFSET); // Read PTO (31-16), SFDTO (15-0)
|
3823 |
counters->PTO = (temp >> 16) & 0xFFF; |
3824 |
counters->SFDTO = temp & 0xFFF;
|
3825 |
|
3826 |
temp = dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_FWTO_OFFSET); // Read RX TO (31-16), TXFRAME (15-0)
|
3827 |
counters->TXF = (temp >> 16) & 0xFFF; |
3828 |
counters->RTO = temp & 0xFFF;
|
3829 |
|
3830 |
temp = dwt_read32bitoffsetreg(DIG_DIAG_ID, EVC_HPW_OFFSET); // Read half period warning events
|
3831 |
counters->HPW = temp & 0xFFF;
|
3832 |
counters->TXW = (temp >> 16) & 0xFFF; // Power-up warning events |
3833 |
|
3834 |
} |
3835 |
|
3836 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3837 |
* @fn dwt_rxreset()
|
3838 |
*
|
3839 |
* @brief this function resets the receiver of the DW1000
|
3840 |
*
|
3841 |
* input parameters:
|
3842 |
*
|
3843 |
* output parameters
|
3844 |
*
|
3845 |
* no return value
|
3846 |
*/
|
3847 |
void dwt_rxreset(void) |
3848 |
{ |
3849 |
// Set RX reset
|
3850 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_SOFTRESET_OFFSET, PMSC_CTRL0_RESET_RX); |
3851 |
|
3852 |
// Clear RX reset
|
3853 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_SOFTRESET_OFFSET, PMSC_CTRL0_RESET_CLEAR); |
3854 |
} |
3855 |
|
3856 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3857 |
* @fn dwt_softreset()
|
3858 |
*
|
3859 |
* @brief this function resets the DW1000
|
3860 |
*
|
3861 |
* input parameters:
|
3862 |
*
|
3863 |
* output parameters
|
3864 |
*
|
3865 |
* no return value
|
3866 |
*/
|
3867 |
void dwt_softreset(void) |
3868 |
{ |
3869 |
_dwt_disablesequencing(); |
3870 |
|
3871 |
// Clear any AON auto download bits (as reset will trigger AON download)
|
3872 |
dwt_write16bitoffsetreg(AON_ID, AON_WCFG_OFFSET, 0x00);
|
3873 |
// Clear the wake-up configuration
|
3874 |
dwt_write8bitoffsetreg(AON_ID, AON_CFG0_OFFSET, 0x00);
|
3875 |
// Upload the new configuration
|
3876 |
_dwt_aonarrayupload(); |
3877 |
|
3878 |
// Reset HIF, TX, RX and PMSC
|
3879 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_SOFTRESET_OFFSET, PMSC_CTRL0_RESET_ALL); |
3880 |
|
3881 |
// DW1000 needs a 10us sleep to let clk PLL lock after reset - the PLL will automatically lock after the reset
|
3882 |
// Could also have polled the PLL lock flag, but then the SPI needs to be < 3MHz !! So a simple delay is easier
|
3883 |
deca_sleep(1);
|
3884 |
|
3885 |
// Clear reset
|
3886 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_SOFTRESET_OFFSET, PMSC_CTRL0_RESET_CLEAR); |
3887 |
|
3888 |
pdw1000local->wait4resp = 0;
|
3889 |
} |
3890 |
|
3891 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3892 |
* @fn dwt_setxtaltrim()
|
3893 |
*
|
3894 |
* @brief This is used to adjust the crystal frequency
|
3895 |
*
|
3896 |
* input parameters:
|
3897 |
* @param value - crystal trim value (in range 0x0 to 0x1F) 31 steps (~1.5ppm per step)
|
3898 |
*
|
3899 |
* output parameters
|
3900 |
*
|
3901 |
* no return value
|
3902 |
*/
|
3903 |
void dwt_setxtaltrim(uint8_t value)
|
3904 |
{ |
3905 |
// The 3 MSb in this 8-bit register must be kept to 0b011 to avoid any malfunction.
|
3906 |
uint8_t reg_val = (3 << 5) | (value & FS_XTALT_MASK); |
3907 |
dwt_write8bitoffsetreg(FS_CTRL_ID, FS_XTALT_OFFSET, reg_val); |
3908 |
} |
3909 |
|
3910 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3911 |
* @fn dwt_getinitxtaltrim()
|
3912 |
*
|
3913 |
* @brief This function returns the value of XTAL trim that has been applied during initialisation (dwt_init). This can
|
3914 |
* be either the value read in OTP memory or a default value.
|
3915 |
*
|
3916 |
* NOTE: The value returned by this function is the initial value only! It is not updated on dwt_setxtaltrim calls.
|
3917 |
*
|
3918 |
* input parameters
|
3919 |
*
|
3920 |
* output parameters
|
3921 |
*
|
3922 |
* returns the XTAL trim value set upon initialisation
|
3923 |
*/
|
3924 |
uint8_t dwt_getinitxtaltrim(void)
|
3925 |
{ |
3926 |
return pdw1000local->init_xtrim;
|
3927 |
} |
3928 |
|
3929 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3930 |
* @fn dwt_configcwmode()
|
3931 |
*
|
3932 |
* @brief this function sets the DW1000 to transmit cw signal at specific channel frequency
|
3933 |
*
|
3934 |
* input parameters:
|
3935 |
* @param chan - specifies the operating channel (e.g. 1, 2, 3, 4, 5, 6 or 7)
|
3936 |
*
|
3937 |
* output parameters
|
3938 |
*
|
3939 |
* no return value
|
3940 |
*/
|
3941 |
void dwt_configcwmode(uint8_t chan)
|
3942 |
{ |
3943 |
#ifdef DWT_API_ERROR_CHECK
|
3944 |
assert((chan >= 1) && (chan <= 7) && (chan != 6)); |
3945 |
#endif
|
3946 |
|
3947 |
//
|
3948 |
// Disable TX/RX RF block sequencing (needed for cw frame mode)
|
3949 |
//
|
3950 |
_dwt_disablesequencing(); |
3951 |
|
3952 |
// Config RF pll (for a given channel)
|
3953 |
// Configure PLL2/RF PLL block CFG/TUNE
|
3954 |
dwt_write32bitoffsetreg(FS_CTRL_ID, FS_PLLCFG_OFFSET, fs_pll_cfg[chan_idx[chan]]); |
3955 |
dwt_write8bitoffsetreg(FS_CTRL_ID, FS_PLLTUNE_OFFSET, fs_pll_tune[chan_idx[chan]]); |
3956 |
// PLL wont be enabled until a TX/RX enable is issued later on
|
3957 |
// Configure RF TX blocks (for specified channel and prf)
|
3958 |
// Config RF TX control
|
3959 |
dwt_write32bitoffsetreg(RF_CONF_ID, RF_TXCTRL_OFFSET, tx_config[chan_idx[chan]]); |
3960 |
|
3961 |
//
|
3962 |
// Enable RF PLL
|
3963 |
//
|
3964 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXPLLPOWEN_MASK); // Enable LDO and RF PLL blocks
|
3965 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXALLEN_MASK); // Enable the rest of TX blocks
|
3966 |
|
3967 |
//
|
3968 |
// Configure TX clocks
|
3969 |
//
|
3970 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, 0x22);
|
3971 |
dwt_write8bitoffsetreg(PMSC_ID, 0x1, 0x07); |
3972 |
|
3973 |
// Disable fine grain TX sequencing
|
3974 |
dwt_setfinegraintxseq(0);
|
3975 |
|
3976 |
// Configure CW mode
|
3977 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGTEST_OFFSET, TC_PGTEST_CW); |
3978 |
} |
3979 |
|
3980 |
/*! ------------------------------------------------------------------------------------------------------------------
|
3981 |
* @fn dwt_configcontinuousframemode()
|
3982 |
*
|
3983 |
* @brief this function sets the DW1000 to continuous tx frame mode for regulatory approvals testing.
|
3984 |
*
|
3985 |
* input parameters:
|
3986 |
* @param framerepetitionrate - This is a 32-bit value that is used to set the interval between transmissions.
|
3987 |
* The minimum value is 4. The units are approximately 8 ns. (or more precisely 512/(499.2e6*128) seconds)).
|
3988 |
*
|
3989 |
* output parameters
|
3990 |
*
|
3991 |
* no return value
|
3992 |
*/
|
3993 |
void dwt_configcontinuousframemode(uint32_t framerepetitionrate)
|
3994 |
{ |
3995 |
//
|
3996 |
// Disable TX/RX RF block sequencing (needed for continuous frame mode)
|
3997 |
//
|
3998 |
_dwt_disablesequencing(); |
3999 |
|
4000 |
//
|
4001 |
// Enable RF PLL and TX blocks
|
4002 |
//
|
4003 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXPLLPOWEN_MASK); // Enable LDO and RF PLL blocks
|
4004 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXALLEN_MASK); // Enable the rest of TX blocks
|
4005 |
|
4006 |
//
|
4007 |
// Configure TX clocks
|
4008 |
//
|
4009 |
_dwt_enableclocks(FORCE_SYS_PLL); |
4010 |
_dwt_enableclocks(FORCE_TX_PLL); |
4011 |
|
4012 |
// Set the frame repetition rate
|
4013 |
if(framerepetitionrate < 4) |
4014 |
{ |
4015 |
framerepetitionrate = 4;
|
4016 |
} |
4017 |
dwt_write32bitreg(DX_TIME_ID, framerepetitionrate); |
4018 |
|
4019 |
//
|
4020 |
// Configure continuous frame TX
|
4021 |
//
|
4022 |
dwt_write8bitoffsetreg(DIG_DIAG_ID, DIAG_TMC_OFFSET, (uint8_t)(DIAG_TMC_TX_PSTM)); // Turn the tx power spectrum test mode - continuous sending of frames
|
4023 |
} |
4024 |
|
4025 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4026 |
* @fn dwt_readtempvbat()
|
4027 |
*
|
4028 |
* @brief this function reads the battery voltage and temperature of the MP
|
4029 |
* The values read here will be the current values sampled by DW1000 AtoD converters.
|
4030 |
* Note on Temperature: the temperature value needs to be converted to give the real temperature
|
4031 |
* the formula is: 1.13 * reading - 113.0
|
4032 |
* Note on Voltage: the voltage value needs to be converted to give the real voltage
|
4033 |
* the formula is: 0.0057 * reading + 2.3
|
4034 |
*
|
4035 |
* NB: To correctly read the temperature this read should be done with xtal clock
|
4036 |
* however that means that the receiver will be switched off, if receiver needs to be on then
|
4037 |
* the timer is used to make sure the value is stable before reading
|
4038 |
*
|
4039 |
* input parameters:
|
4040 |
* @param fastSPI - set to 1 if SPI rate > than 3MHz is used
|
4041 |
*
|
4042 |
* output parameters
|
4043 |
*
|
4044 |
* returns (temp_raw<<8)|(vbat_raw)
|
4045 |
*/
|
4046 |
uint16_t dwt_readtempvbat(uint8_t fastSPI) |
4047 |
{ |
4048 |
uint8_t wr_buf[2];
|
4049 |
uint8_t vbat_raw; |
4050 |
uint8_t temp_raw; |
4051 |
|
4052 |
// These writes should be single writes and in sequence
|
4053 |
wr_buf[0] = 0x80; // Enable TLD Bias |
4054 |
dwt_writetodevice(RF_CONF_ID,0x11,1,wr_buf); |
4055 |
|
4056 |
wr_buf[0] = 0x0A; // Enable TLD Bias and ADC Bias |
4057 |
dwt_writetodevice(RF_CONF_ID,0x12,1,wr_buf); |
4058 |
|
4059 |
wr_buf[0] = 0x0f; // Enable Outputs (only after Biases are up and running) |
4060 |
dwt_writetodevice(RF_CONF_ID,0x12,1,wr_buf); // |
4061 |
|
4062 |
// Reading All SAR inputs
|
4063 |
wr_buf[0] = 0x00; |
4064 |
dwt_writetodevice(TX_CAL_ID, TC_SARL_SAR_C,1,wr_buf);
|
4065 |
wr_buf[0] = 0x01; // Set SAR enable |
4066 |
dwt_writetodevice(TX_CAL_ID, TC_SARL_SAR_C,1,wr_buf);
|
4067 |
|
4068 |
if(fastSPI == 1) |
4069 |
{ |
4070 |
deca_sleep(1); // If using PLL clocks(and fast SPI rate) then this sleep is needed |
4071 |
// Read voltage and temperature.
|
4072 |
dwt_readfromdevice(TX_CAL_ID, TC_SARL_SAR_LVBAT_OFFSET,2,wr_buf);
|
4073 |
} |
4074 |
else //change to a slow clock |
4075 |
{ |
4076 |
_dwt_enableclocks(FORCE_SYS_XTI); // NOTE: set system clock to XTI - this is necessary to make sure the values read are reliable
|
4077 |
// Read voltage and temperature.
|
4078 |
dwt_readfromdevice(TX_CAL_ID, TC_SARL_SAR_LVBAT_OFFSET,2,wr_buf);
|
4079 |
// Default clocks (ENABLE_ALL_SEQ)
|
4080 |
_dwt_enableclocks(ENABLE_ALL_SEQ); // Enable clocks for sequencing
|
4081 |
} |
4082 |
|
4083 |
vbat_raw = wr_buf[0];
|
4084 |
temp_raw = wr_buf[1];
|
4085 |
|
4086 |
wr_buf[0] = 0x00; // Clear SAR enable |
4087 |
dwt_writetodevice(TX_CAL_ID, TC_SARL_SAR_C,1,wr_buf);
|
4088 |
|
4089 |
return (uint16_t)((temp_raw<<8)|(vbat_raw)); |
4090 |
} |
4091 |
|
4092 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4093 |
* @fn dwt_readwakeuptemp()
|
4094 |
*
|
4095 |
* @brief this function reads the temperature of the DW1000 that was sampled
|
4096 |
* on waking from Sleep/Deepsleep. They are not current values, but read on last
|
4097 |
* wakeup if DWT_TANDV bit is set in mode parameter of dwt_configuresleep
|
4098 |
*
|
4099 |
* input parameters:
|
4100 |
*
|
4101 |
* output parameters:
|
4102 |
*
|
4103 |
* returns: 8-bit raw temperature sensor value
|
4104 |
*/
|
4105 |
uint8_t dwt_readwakeuptemp(void)
|
4106 |
{ |
4107 |
return dwt_read8bitoffsetreg(TX_CAL_ID, TC_SARL_SAR_LTEMP_OFFSET);
|
4108 |
} |
4109 |
|
4110 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4111 |
* @fn dwt_readwakeupvbat()
|
4112 |
*
|
4113 |
* @brief this function reads the battery voltage of the DW1000 that was sampled
|
4114 |
* on waking from Sleep/Deepsleep. They are not current values, but read on last
|
4115 |
* wakeup if DWT_TANDV bit is set in mode parameter of dwt_configuresleep
|
4116 |
*
|
4117 |
* input parameters:
|
4118 |
*
|
4119 |
* output parameters:
|
4120 |
*
|
4121 |
* returns: 8-bit raw battery voltage sensor value
|
4122 |
*/
|
4123 |
uint8_t dwt_readwakeupvbat(void)
|
4124 |
{ |
4125 |
return dwt_read8bitoffsetreg(TX_CAL_ID, TC_SARL_SAR_LVBAT_OFFSET);
|
4126 |
} |
4127 |
|
4128 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4129 |
* @fn dwt_calcbandwidthtempadj()
|
4130 |
*
|
4131 |
* @brief this function determines the corrected bandwidth setting (PG_DELAY register setting)
|
4132 |
* of the DW1000 which changes over temperature.
|
4133 |
*
|
4134 |
* input parameters:
|
4135 |
* @param target_count - uint16_t - the PG count target to reach in order to correct the bandwidth
|
4136 |
*
|
4137 |
* output parameters:
|
4138 |
*
|
4139 |
* returns: (uint32) The setting to be programmed into the PG_DELAY value
|
4140 |
*/
|
4141 |
uint32_t dwt_calcbandwidthtempadj(uint16_t target_count) |
4142 |
{ |
4143 |
int i;
|
4144 |
uint32_t bit_field, curr_bw; |
4145 |
int32_t delta_count = 0;
|
4146 |
uint32_t best_bw = 0;
|
4147 |
uint16_t raw_count = 0;
|
4148 |
int32_t delta_lowest; |
4149 |
|
4150 |
// Used to store the current values of the registers so that they can be restored after
|
4151 |
uint8_t old_pmsc_ctrl0; |
4152 |
uint16_t old_pmsc_ctrl1; |
4153 |
uint32_t old_rf_conf_txpow_mask; |
4154 |
|
4155 |
// Record the current values of these registers, to restore later
|
4156 |
old_pmsc_ctrl0 = dwt_read8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET); |
4157 |
old_pmsc_ctrl1 = dwt_read16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET); |
4158 |
old_rf_conf_txpow_mask = dwt_read32bitreg(RF_CONF_ID); |
4159 |
|
4160 |
// Set clock to XTAL
|
4161 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, PMSC_CTRL0_SYSCLKS_19M); |
4162 |
|
4163 |
// Disable sequencing
|
4164 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, PMSC_CTRL1_PKTSEQ_DISABLE); |
4165 |
|
4166 |
// Turn on CLK PLL, Mix Bias and PG
|
4167 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXPOW_MASK | RF_CONF_PGMIXBIASEN_MASK); |
4168 |
|
4169 |
// Set sys and TX clock to PLL
|
4170 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, PMSC_CTRL0_SYSCLKS_125M | PMSC_CTRL0_TXCLKS_125M); |
4171 |
|
4172 |
// Set the MSB high for first guess
|
4173 |
curr_bw = 0x80;
|
4174 |
// Set starting bit
|
4175 |
bit_field = 0x80;
|
4176 |
// Initial lowest delta is the maximum difference that we should allow the count value to be from the target.
|
4177 |
// If the algorithm is successful, it will be overwritten by a smaller value where the count value is closer
|
4178 |
// to the target
|
4179 |
delta_lowest = 300;
|
4180 |
|
4181 |
for (i = 0; i < 7; i++) |
4182 |
{ |
4183 |
// start with 0xc0 and test.
|
4184 |
bit_field = bit_field >> 1;
|
4185 |
curr_bw = curr_bw | bit_field; |
4186 |
|
4187 |
// Write bw setting to PG_DELAY register
|
4188 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGDELAY_OFFSET,(uint8_t)curr_bw); |
4189 |
|
4190 |
// Set cal direction and time
|
4191 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGCCTRL_OFFSET, TC_PGCCTRL_DIR_CONV | TC_PGCCTRL_TMEAS_MASK); |
4192 |
|
4193 |
// Start cal
|
4194 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGCCTRL_OFFSET, TC_PGCCTRL_DIR_CONV | TC_PGCCTRL_TMEAS_MASK | TC_PGCCTRL_CALSTART); |
4195 |
// Allow cal to complete
|
4196 |
deca_sleep(100);
|
4197 |
|
4198 |
// Read count value from the PG cal block
|
4199 |
raw_count = dwt_read16bitoffsetreg(TX_CAL_ID, TC_PGCAL_STATUS_OFFSET) & TC_PGCAL_STATUS_DELAY_MASK; |
4200 |
|
4201 |
// lets keep track of the closest value to the target in case we overshoot
|
4202 |
delta_count = abs((int)raw_count - (int)target_count); |
4203 |
if (delta_count < delta_lowest)
|
4204 |
{ |
4205 |
delta_lowest = delta_count; |
4206 |
best_bw = curr_bw; |
4207 |
} |
4208 |
|
4209 |
// Test the count results
|
4210 |
if (raw_count > target_count)
|
4211 |
// Count was lower, BW was lower so increase PG DELAY
|
4212 |
curr_bw = curr_bw | bit_field; |
4213 |
else
|
4214 |
// Count was higher
|
4215 |
curr_bw = curr_bw & (~(bit_field)); |
4216 |
} |
4217 |
|
4218 |
// Restore old register values
|
4219 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, old_pmsc_ctrl0); |
4220 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, old_pmsc_ctrl1); |
4221 |
dwt_write32bitreg(RF_CONF_ID, old_rf_conf_txpow_mask); |
4222 |
|
4223 |
// Returns the best PG_DELAY setting
|
4224 |
return best_bw;
|
4225 |
} |
4226 |
|
4227 |
|
4228 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4229 |
* @fn _dwt_computetxpowersetting()
|
4230 |
*
|
4231 |
* @brief this function calculates the appropriate change to the TX_POWER register to compensate
|
4232 |
* the TX power output at different temperatures.
|
4233 |
*
|
4234 |
* input parameters:
|
4235 |
* @param ref_powerreg - uint32_t - the TX_POWER register value recorded when reference measurements were made
|
4236 |
* @param power_adj - uint32_t - the adjustment in power level to be made, in 0.5dB steps
|
4237 |
*
|
4238 |
* output parameters:
|
4239 |
*
|
4240 |
* returns: (uint32) The setting to be programmed into the TX_POWER register
|
4241 |
*/
|
4242 |
uint32_t _dwt_computetxpowersetting(uint32_t ref_powerreg, int32_t power_adj) |
4243 |
{ |
4244 |
int32_t da_attn_change, mixer_gain_change; |
4245 |
uint8_t current_da_attn, current_mixer_gain; |
4246 |
uint8_t new_da_attn, new_mixer_gain; |
4247 |
uint32_t new_regval = 0;
|
4248 |
int i;
|
4249 |
|
4250 |
for(i = 0; i < 4; i++) |
4251 |
{ |
4252 |
da_attn_change = 0;
|
4253 |
mixer_gain_change = power_adj; |
4254 |
current_da_attn = ((ref_powerreg >> (i*8)) & 0xE0) >> 5; |
4255 |
current_mixer_gain = (ref_powerreg >> (i*8)) & 0x1F; |
4256 |
|
4257 |
// Mixer gain gives best performance between 4 and 20
|
4258 |
while((current_mixer_gain + mixer_gain_change < 4) || |
4259 |
(current_mixer_gain + mixer_gain_change > 20))
|
4260 |
{ |
4261 |
// If mixer gain goes outside bounds, adjust the DA attenuation to compensate
|
4262 |
if(current_mixer_gain + mixer_gain_change > 20) |
4263 |
{ |
4264 |
da_attn_change += 1;
|
4265 |
mixer_gain_change -= (int) (DA_ATTN_STEP / MIXER_GAIN_STEP);
|
4266 |
} |
4267 |
else if(current_mixer_gain + mixer_gain_change < 4) |
4268 |
{ |
4269 |
da_attn_change += 1;
|
4270 |
mixer_gain_change += (int) (DA_ATTN_STEP / MIXER_GAIN_STEP);
|
4271 |
} |
4272 |
} |
4273 |
|
4274 |
new_da_attn = current_da_attn + (uint8_t)da_attn_change; |
4275 |
new_mixer_gain = current_mixer_gain + (uint8_t)mixer_gain_change; |
4276 |
|
4277 |
new_regval |= ((uint32_t) ((new_da_attn << 5) | new_mixer_gain)) << (i * 8); |
4278 |
} |
4279 |
|
4280 |
return (uint32_t)new_regval;
|
4281 |
} |
4282 |
|
4283 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4284 |
* @fn dwt_calcpowertempadj()
|
4285 |
*
|
4286 |
* @brief this function determines the corrected power setting (TX_POWER setting) for the
|
4287 |
* DW1000 which changes over temperature.
|
4288 |
*
|
4289 |
* input parameters:
|
4290 |
* @param channel - uint8_t - the channel at which compensation of power level will be applied
|
4291 |
* @param ref_powerreg - uint32_t - the TX_POWER register value recorded when reference measurements were made
|
4292 |
* @param current_temperature - double - the current ambient temperature in degrees Celcius
|
4293 |
* @param reference_temperature - double - the temperature at which reference measurements were made
|
4294 |
* output parameters: None
|
4295 |
*
|
4296 |
* returns: (uint32) The corrected TX_POWER register value
|
4297 |
*/
|
4298 |
uint32_t dwt_calcpowertempadj |
4299 |
( |
4300 |
uint8_t channel, |
4301 |
uint32_t ref_powerreg, |
4302 |
double curr_temp,
|
4303 |
double ref_temp
|
4304 |
) |
4305 |
{ |
4306 |
double delta_temp;
|
4307 |
double delta_power;
|
4308 |
|
4309 |
// Find the temperature differential
|
4310 |
delta_temp = curr_temp - ref_temp; |
4311 |
|
4312 |
// Calculate the expected power differential at the current temperature
|
4313 |
delta_power = delta_temp * txpwr_compensation[chan_idx[channel]]; |
4314 |
|
4315 |
// Adjust the TX_POWER register value
|
4316 |
return _dwt_computetxpowersetting(ref_powerreg, (int32_t)(delta_power / MIXER_GAIN_STEP));
|
4317 |
} |
4318 |
|
4319 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4320 |
* @fn dwt_calcpgcount()
|
4321 |
*
|
4322 |
* @brief this function calculates the value in the pulse generator counter register (PGC_STATUS) for a given PG_DELAY
|
4323 |
* This is used to take a reference measurement, and the value recorded as the reference is used to adjust the
|
4324 |
* bandwidth of the device when the temperature changes.
|
4325 |
*
|
4326 |
* input parameters:
|
4327 |
* @param pgdly - uint8_t - the PG_DELAY to set (to control bandwidth), and to find the corresponding count value for
|
4328 |
* output parameters: None
|
4329 |
*
|
4330 |
* returns: (uint16) PGC_STATUS count value calculated from the provided PG_DELAY value - used as reference for later
|
4331 |
* bandwidth adjustments
|
4332 |
*/
|
4333 |
uint16_t dwt_calcpgcount(uint8_t pgdly) |
4334 |
{ |
4335 |
// Perform PG count read ten times and take an average to smooth out any noise
|
4336 |
const int NUM_SAMPLES = 10; |
4337 |
uint32_t sum_count = 0;
|
4338 |
uint16_t average_count = 0, count = 0; |
4339 |
int i = 0; |
4340 |
|
4341 |
// Used to store the current values of the registers so that they can be restored after
|
4342 |
uint8_t old_pmsc_ctrl0; |
4343 |
uint16_t old_pmsc_ctrl1; |
4344 |
uint32_t old_rf_conf_txpow_mask; |
4345 |
|
4346 |
// Record the current values of these registers, to restore later
|
4347 |
old_pmsc_ctrl0 = dwt_read8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET); |
4348 |
old_pmsc_ctrl1 = dwt_read16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET); |
4349 |
old_rf_conf_txpow_mask = dwt_read32bitreg(RF_CONF_ID); |
4350 |
|
4351 |
// Set clock to XTAL
|
4352 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, PMSC_CTRL0_SYSCLKS_19M); |
4353 |
// Disable sequencing
|
4354 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, PMSC_CTRL1_PKTSEQ_DISABLE); |
4355 |
// Turn on CLK PLL, Mix Bias and PG
|
4356 |
dwt_write32bitreg(RF_CONF_ID, RF_CONF_TXPOW_MASK | RF_CONF_PGMIXBIASEN_MASK); |
4357 |
// Set sys and TX clock to PLL
|
4358 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, PMSC_CTRL0_SYSCLKS_125M | PMSC_CTRL0_TXCLKS_125M); |
4359 |
|
4360 |
for(i = 0; i < NUM_SAMPLES; i++) { |
4361 |
// Write bw setting to PG_DELAY register
|
4362 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGDELAY_OFFSET, pgdly); |
4363 |
|
4364 |
// Set cal direction and time
|
4365 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGCCTRL_OFFSET, TC_PGCCTRL_DIR_CONV | TC_PGCCTRL_TMEAS_MASK); |
4366 |
|
4367 |
// Start cal
|
4368 |
dwt_write8bitoffsetreg(TX_CAL_ID, TC_PGCCTRL_OFFSET, TC_PGCCTRL_DIR_CONV | TC_PGCCTRL_TMEAS_MASK | TC_PGCCTRL_CALSTART); |
4369 |
|
4370 |
// Allow cal to complete - the TC_PGCCTRL_CALSTART bit will clear automatically
|
4371 |
deca_sleep(100);
|
4372 |
|
4373 |
// Read count value from the PG cal block
|
4374 |
count = dwt_read16bitoffsetreg(TX_CAL_ID, TC_PGCAL_STATUS_OFFSET) & TC_PGCAL_STATUS_DELAY_MASK; |
4375 |
|
4376 |
sum_count += count; |
4377 |
} |
4378 |
|
4379 |
// Restore old register values
|
4380 |
dwt_write8bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, old_pmsc_ctrl0); |
4381 |
dwt_write16bitoffsetreg(PMSC_ID, PMSC_CTRL1_OFFSET, old_pmsc_ctrl1); |
4382 |
dwt_write32bitreg(RF_CONF_ID, old_rf_conf_txpow_mask); |
4383 |
|
4384 |
average_count = (uint16_t)(sum_count / NUM_SAMPLES); |
4385 |
return average_count;
|
4386 |
} |
4387 |
|
4388 |
|
4389 |
/* ===============================================================================================
|
4390 |
List of expected (known) device ID handled by this software
|
4391 |
===============================================================================================
|
4392 |
|
4393 |
0xDECA0130 // DW1000 - MP
|
4394 |
|
4395 |
=============================================================================================== */
|
4396 |
|
4397 |
/****************************************************************************************************************************************************
|
4398 |
*
|
4399 |
* Declaration of platform-dependent lower level functions.
|
4400 |
*
|
4401 |
****************************************************************************************************************************************************/
|
4402 |
|
4403 |
/****************************************************************************//** |
4404 |
*
|
4405 |
* alld_dw1000.c SPI Section
|
4406 |
*
|
4407 |
*******************************************************************************/
|
4408 |
|
4409 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4410 |
* Function: writetospi()
|
4411 |
*
|
4412 |
* Low level abstract function for DW1000 to write to the SPI
|
4413 |
* Takes two separate byte buffers for write header and write data
|
4414 |
* returns 0 for success, or -1 for error
|
4415 |
*/
|
4416 |
#pragma GCC optimize ("O3") |
4417 |
static int writetospi(uint16_t headerLength, |
4418 |
const uint8_t *headerBuffer,
|
4419 |
uint32_t bodyLength, |
4420 |
const uint8_t *bodyBuffer)
|
4421 |
{ |
4422 |
uint8_t buffer[SPIBUFFLEN]; |
4423 |
memcpy(buffer, headerBuffer, headerLength); //copy header (register id no.) to the buffer
|
4424 |
memcpy(&buffer[headerLength], bodyBuffer, bodyLength); //copy data to the buffer
|
4425 |
|
4426 |
apalSPITransmit(pdw1000local->driver->spid, |
4427 |
buffer, |
4428 |
bodyLength + headerLength); // send header (register id) and data
|
4429 |
|
4430 |
return 0; |
4431 |
} // end writetospi()
|
4432 |
|
4433 |
|
4434 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4435 |
* Function: readfromspi()
|
4436 |
*
|
4437 |
* Low level abstract function for DW1000 to read from the SPI
|
4438 |
* Takes two separate byte buffers for write header and read data
|
4439 |
* returns the offset into read buffer where first byte of read data may be found,
|
4440 |
* or returns -1 if there was an error
|
4441 |
*/
|
4442 |
#pragma GCC optimize ("O3") |
4443 |
static int readfromspi(uint16_t headerLength, |
4444 |
const uint8_t *headerBuffer,
|
4445 |
uint32_t readlength, |
4446 |
uint8_t *readBuffer) |
4447 |
{ |
4448 |
|
4449 |
apalSPITransmitAndReceive(pdw1000local->driver->spid, |
4450 |
headerBuffer, |
4451 |
readBuffer, |
4452 |
headerLength, |
4453 |
readlength); |
4454 |
|
4455 |
return 0; |
4456 |
} // end readfromspi()
|
4457 |
|
4458 |
/****************************************************************************//** |
4459 |
*
|
4460 |
* alld_dw1000.c IRQ section
|
4461 |
*
|
4462 |
*******************************************************************************/
|
4463 |
|
4464 |
|
4465 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4466 |
* Function: decamutexon()
|
4467 |
*
|
4468 |
* Description: This function should disable interrupts. This is called at the start of a critical section
|
4469 |
* It returns the irq state before disable, this value is used to re-enable in decamutexoff call
|
4470 |
*
|
4471 |
* Note: The body of this function is platform specific
|
4472 |
*
|
4473 |
* input parameters:
|
4474 |
*
|
4475 |
* output parameters
|
4476 |
*
|
4477 |
* returns the state of the DW1000 interrupt
|
4478 |
*/
|
4479 |
decaIrqStatus_t decamutexon(void)
|
4480 |
{ |
4481 |
|
4482 |
decaIrqStatus_t s = port_GetEXT_IRQStatus(); |
4483 |
if(s) {
|
4484 |
port_DisableEXT_IRQ(); //disable the external interrupt line
|
4485 |
} |
4486 |
return s ; // return state before disable, value is used to re-enable in decamutexoff call |
4487 |
} |
4488 |
|
4489 |
/*! ------------------------------------------------------------------------------------------------------------------
|
4490 |
* Function: decamutexoff()
|
4491 |
*
|
4492 |
* Description: This function should re-enable interrupts, or at least restore their state as returned(&saved) by decamutexon
|
4493 |
* This is called at the end of a critical section
|
4494 |
*
|
4495 |
* Note: The body of this function is platform specific
|
4496 |
*
|
4497 |
* input parameters:
|
4498 |
* @param s - the state of the DW1000 interrupt as returned by decamutexon
|
4499 |
*
|
4500 |
* output parameters
|
4501 |
*
|
4502 |
* returns the state of the DW1000 interrupt
|
4503 |
*/
|
4504 |
void decamutexoff(decaIrqStatus_t s)
|
4505 |
{ |
4506 |
// (void) s;
|
4507 |
if(s) { //need to check the port state as we can't use level sensitive interrupt on the STM ARM |
4508 |
port_EnableEXT_IRQ(); |
4509 |
} |
4510 |
return;
|
4511 |
} |
4512 |
|
4513 |
|
4514 |
/*! Wrapper function to be used by decadriver. Declared in deca_device_api.h
|
4515 |
*
|
4516 |
*/
|
4517 |
|
4518 |
/*! @brief sleep or idle the thread in millisecond */
|
4519 |
void deca_sleep(unsigned int time_ms) |
4520 |
{ |
4521 |
apalSleep(time_ms * 1000);
|
4522 |
} |
4523 |
|
4524 |
/*! @brief sleep or idle the thread in millisecond */
|
4525 |
void Sleep(unsigned int time_ms) |
4526 |
{ |
4527 |
apalSleep(time_ms * 1000);
|
4528 |
} |
4529 |
|
4530 |
|
4531 |
void port_wakeup_dw1000_fast(){ // NOT SUPPORTED |
4532 |
return;
|
4533 |
} |
4534 |
|
4535 |
/*! @brief Get the current system tick time */
|
4536 |
uint32_t portGetTickCnt(){ |
4537 |
return chVTGetSystemTimeX();
|
4538 |
} |
4539 |
|
4540 |
/*! @brief Disable the interrupt handler */
|
4541 |
void port_DisableEXT_IRQ(void){ |
4542 |
nvicDisableVector(DW1000_EXTI_IRQn); |
4543 |
} |
4544 |
|
4545 |
/*! @brief Enable the interrupt handler */
|
4546 |
void port_EnableEXT_IRQ(void){ |
4547 |
nvicEnableVector(DW1000_EXTI_IRQn, STM32_IRQ_EXTI10_15_PRIORITY); |
4548 |
} |
4549 |
|
4550 |
/*! @brief Get the current status of the interrupt handler */
|
4551 |
decaIrqStatus_t port_GetEXT_IRQStatus(void){
|
4552 |
decaIrqStatus_t bitstatus = RESET; |
4553 |
|
4554 |
if(NVIC_GetActive(DW1000_EXTI_IRQn)|| NVIC_GetPendingIRQ(DW1000_EXTI_IRQn)){
|
4555 |
bitstatus = SET; //Interrupt is active or panding
|
4556 |
} |
4557 |
else {
|
4558 |
bitstatus = RESET; //No interrupt IRQ at the moment
|
4559 |
} |
4560 |
|
4561 |
return bitstatus;
|
4562 |
} |
4563 |
|