Revision 88449987 unittests/periphery-lld/src/ut_alld_DW1000_v1.c

View differences:

unittests/periphery-lld/src/ut_alld_DW1000_v1.c
27 27
#include <module.h>
28 28
#include <alld_DW1000.h>
29 29
#include <v1/deca_instance_v1.h>
30
#include <v1/alld_dw1000_regs_v1.h>
31
#include <string.h>
30 32

  
31 33

  
32 34
/******************************************************************************/
......
69 71

  
70 72
/*! @brief Change the SPI speed configuration on the fly */
71 73
void setHighSpeed_SPI(bool speedValue, DW1000Driver* drv){
72

  
73 74
  spiStop(drv->spid);
74

  
75 75
  if (speedValue == FALSE){
76 76
    spiStart(drv->spid, &moduleHalSpiUwbLsConfig);  // low speed spi configuration
77 77
  }
......
80 80
  }
81 81
}
82 82

  
83
/*! @brief entry point to the IRQn event in DW1000 module
84
 *
85
 * */
83
/*! @brief entry point to the IRQn event in DW1000 module */
86 84
void process_deca_irq(void){
87 85
  do{
88 86
    dwt_isr();
......
90 88
  }while(port_CheckEXT_IRQ() == 1);
91 89
}
92 90

  
93
/*! @brief Check the current value of GPIO pin and return the value */
94
apalGpioState_t port_CheckEXT_IRQ(void) {
95
  apalGpioState_t  val;
96
  apalGpioRead(moduleGpioDw1000Irqn.gpio, &val);
97
  return val;
98
}
99

  
100 91
/*! @brief Manually set the chip select pin of the SPI */
101 92
void set_SPI_chip_select(void){
102 93
  apalGpioWrite(moduleGpioSpiChipSelect.gpio, APAL_GPIO_HIGH);
......
109 100

  
110 101
/*! @brief Manually reset the DW1000 module  */
111 102
void reset_DW1000(void){
112

  
113 103
  // Set the pin as output
114 104
  palSetLineMode(moduleGpioDw1000Reset.gpio->line, APAL_GPIO_DIRECTION_OUTPUT);
115

  
116 105
  //drive the RSTn pin low
117 106
  apalGpioWrite(moduleGpioDw1000Reset.gpio, APAL_GPIO_LOW);
118

  
119 107
  //put the pin back to tri-state ... as input
120 108
//  palSetLineMode(moduleGpioDw1000Reset.gpio->line, APAL_GPIO_DIRECTION_INPUT); // TODO:
109
  aosThdMSleep(7);
110
}
121 111

  
122
  aosThdMSleep(2);
112
/*! @brief waking up the DW1000 module using Chip Select pin */
113
void wakeup_DW1000(void){
114
  clear_SPI_chip_select();
115
  aosThdMSleep(1);
116
  set_SPI_chip_select();
117
  aosThdMSleep(7);  // wait for XTAL to stabilize
118

  
119
  // set wakeup pin directly high
120
//   apalGpioWrite(moduleGpioDw1000WakeUp.gpio, APAL_GPIO_HIGH);
121
   aosThdMSleep(10);
123 122
}
124 123

  
125 124
/*! @brief Configure instance tag/anchor/etc... addresses */
126 125
void addressconfigure(uint8_t s1switch, uint8_t mode){
127 126
  uint16_t instAddress ;
128

  
129 127
  instance_anchaddr = (((s1switch & SWS1_A1A_MODE) << 2) + (s1switch & SWS1_A2A_MODE) + ((s1switch & SWS1_A3A_MODE) >> 2)) >> 4;
130

  
131 128
  if(mode == ANCHOR) {
132 129
    if(instance_anchaddr > 3) {
133 130
      instAddress = GATEWAY_ANCHOR_ADDR | 0x4 ; //listener
......
139 136
  else{
140 137
    instAddress = (uint16_t)instance_anchaddr;
141 138
  }
142

  
143 139
  instancesetaddresses(instAddress);
144 140
}
145 141

  
146 142
/*! @brief returns the use case / operational mode */
147 143
int decarangingmode(uint8_t s1switch){
148 144
  int mode = 0;
149

  
150 145
  if(s1switch & SWS1_SHF_MODE)  {
151 146
    mode = 1;
152 147
  }
153

  
154 148
  if(s1switch & SWS1_CH5_MODE) {
155 149
    mode = mode + 2;
156 150
  }
157

  
158 151
  return mode;
159 152
}
160 153

  
......
177 170
    }    
178 171
    dwt_softreset();
179 172
  }
180

  
181 173
    reset_DW1000();  //reset the DW1000 by driving the RSTn line low
182

  
183 174
  if((s1switch & SWS1_ANC_MODE) == 0){
184 175
    instance_mode = TAG;
185 176
  }
186 177
  else{
187 178
    instance_mode = ANCHOR;
188 179
  }
189

  
190
  result = instance_init(drv) ;
191

  
180
  result = instance_init(drv);
192 181
  if (0 > result){
193 182
    return(-1) ;
194 183
  }
195

  
196 184
  setHighSpeed_SPI(TRUE, drv);       // high speed spi max. ~ 20M
197 185
  devID = instancereaddeviceid() ;
198

  
199 186
  if (DWT_DEVICE_ID != devID){
200 187
    return(-1) ;
201 188
  }
202

  
203 189
  addressconfigure(s1switch, (uint8_t)instance_mode) ;
204

  
205 190
  if((instance_mode == ANCHOR) && (instance_anchaddr > 0x3)){
206 191
    instance_mode = LISTENER;
207 192
  }
208

  
209 193
  instancesetrole(instance_mode) ;       // Set this instance role
210 194
  dr_mode = decarangingmode(s1switch);
211 195
  chan = chConfig[dr_mode].channelNumber ;
......
227 211
           | S1_SWITCH_OFF << 6  // (configure Tag or anchor ID no.)
228 212
           | S1_SWITCH_OFF << 7; // Not use in this demo
229 213

  
230

  
231 214
  port_DisableEXT_IRQ();           //disable ScenSor IRQ until we configure the device
232

  
233 215
  if(inittestapplication(s1switch, drv) == -1) {
234 216
    return (-1); //error
235 217
  }
236

  
237 218
  aosThdMSleep(5);
238

  
239 219
  port_EnableEXT_IRQ();  //enable DW1000 IRQ before starting
240 220

  
241 221
  return 0;
......
245 225
/******************************************************************************/
246 226
/* EXPORTED FUNCTIONS                                                         */
247 227
/******************************************************************************/
248

  
249

  
250 228
aos_utresult_t utAlldDw1000Func(BaseSequentialStream* stream, aos_unittest_t* ut) {
251 229

  
252 230
  aosDbgCheck(ut->data != NULL);
253

  
254 231
  aos_utresult_t result = {0, 0};
255 232

  
233
#if defined (AMIROLLD_CFG_MIC9404x)
234
  // Enable 3.3 and 1.8 supply voltages for powering up the DW1000 module in AMiRo Light Ring
235
  if ((ut->data != NULL) && (((ut_dw1000data_t*)(ut->data))->mic9404xd != NULL)){
236
    mic9404x_lld_state_t state;
237
    uint32_t status = APAL_STATUS_OK;
238

  
239
    chprintf(stream, "reading current status of the Power..\n");
240
    status = mic9404x_lld_get(((ut_dw1000data_t*)(ut->data))->mic9404xd, &state);
241
    if (status == APAL_STATUS_OK) {
242
      aosUtPassedMsg(stream, &result, "power %s\n", (state == MIC9404x_LLD_STATE_ON) ? "enabled" : "disabled");
243
    } else {
244
      aosUtFailed(stream, &result);
245
    }
246
    if (state == MIC9404x_LLD_STATE_OFF) {
247
      chprintf(stream, "enabling the power ...\n");
248
      status = mic9404x_lld_set(((ut_dw1000data_t*)(ut->data))->mic9404xd, MIC9404x_LLD_STATE_ON);
249
      status |= mic9404x_lld_get(((ut_dw1000data_t*)(ut->data))->mic9404xd, &state);
250
      if (state == MIC9404x_LLD_STATE_ON) {
251
        aosThdSSleep(2);
252
        status |= mic9404x_lld_get(((ut_dw1000data_t*)(ut->data))->mic9404xd, &state);
253
      }
254
      if ((status == APAL_STATUS_OK) && (state == MIC9404x_LLD_STATE_ON)) {
255
        aosUtPassed(stream, &result);
256
      } else {
257
        aosUtFailed(stream, &result);
258
      }
259
    }
260
    aosThdSleep(1);
261
    return result;
262
  }
263
#endif  /* defined (AMIROLLD_CFG_MIC9404x) */
264

  
265

  
266
  // Start the DW1000 module UT after powering up
256 267
  chprintf(stream, "init DW1000...\n");
257
  dwt_initialise(DWT_LOADUCODE, (DW1000Driver*) ut->data);
258
  aosThdMSleep(5);
268
  aosThdSleep(1);
269
  ut_dw1000data_t* h_dw1000data = NULL;
270
  if((ut->data != NULL) && (((ut_dw1000data_t*)(ut->data))->dw1000d != NULL)){
271
    h_dw1000data = ut->data;
272
    chprintf(stream, "assign handle for DW1000Driver struct \n");
273
  }
274
  else {
275
    chprintf(stream, "unsupported data type \n");
276
    return result;
277
  }
278
  aosThdSleep(1);
259 279

  
280
  reset_DW1000();     // hard reset
281
//  wakeup_DW1000();
282
  aosThdMSleep(5);
283
  int init = dwt_initialise(DWT_LOADUCODE, h_dw1000data->dw1000d);
284
  if (init == 0){
285
    chprintf(stream, "DW1000 is initialized \n");
286
  }
287
  else {
288
    chprintf(stream, "init error with return value: %d \n", init);
289
  }
290
  aosThdMSleep(5);
260 291

  
261 292
/*! Unit Test snippets for DW1000.
262 293
 * @Note: Event IRQ for DW1000 should be tested separately
263 294
 */
264 295
#if defined(UNIT_TEST_SNIPPETS_DW1000)
265

  
266
  uint32_t actual_deviceId;
267

  
296
  uint32_t actual_devID;
268 297
  port_DisableEXT_IRQ();
269 298

  
270
  setHighSpeed_SPI(false, (DW1000Driver*) ut->data);
271
  chprintf(stream, "expected device ID (LS SPI): 0xDECA0130 \n");
299
  /*! UT1: Low speed SPI result */
300
  setHighSpeed_SPI(false, h_dw1000data->dw1000d);
301
  chprintf(stream, "expected ID (LS SPI): 0xDECA0130 \n");
272 302
  aosThdMSleep(5);
273
  actual_deviceId = instancereaddeviceid();
274
  chprintf(stream, "actual read ID: 0x%x\n", actual_deviceId);
303
  actual_devID = instancereaddeviceid();
304
  chprintf(stream, "read ID (LS SPI): 0x%x\n", actual_devID);
275 305
  aosThdMSleep(5);
276 306

  
277 307
  //if the read of device ID fails, the DW1000 could be asleep
278
  if(DWT_DEVICE_ID != actual_deviceId){
279

  
308
  if(DWT_DEVICE_ID != actual_devID){
280 309
    clear_SPI_chip_select();
281 310
    aosThdMSleep(1);
282 311
    set_SPI_chip_select();
283 312
    aosThdMSleep(7);
284
    actual_deviceId = instancereaddeviceid() ;
285

  
286
    if(DWT_DEVICE_ID != actual_deviceId){
313
    actual_devID = instancereaddeviceid() ;
314
    if(DWT_DEVICE_ID != actual_devID){
287 315
      chprintf(stream, "SPI is not working or Unsupported Device ID\n");
288
      chprintf(stream, "actual device ID is: 0x%x\n", actual_deviceId);
316
      chprintf(stream, "actual device ID is: 0x%x\n", actual_devID);
289 317
      chprintf(stream, "expected device ID: 0xDECA0130 \n");
290 318
      aosThdMSleep(5);
291
    }
292

  
293
    //clear the sleep bit - so that after the hard reset below the DW does not go into sleep
319
    }   
294 320
    dwt_softreset();
295 321
  }
296 322

  
297
  /*! UT1: Low speed SPI result */
298
  if (actual_deviceId == DWT_DEVICE_ID){
323
  if (actual_devID == DWT_DEVICE_ID){
299 324
    aosUtPassed(stream, &result);
300 325
  } else {
301 326
    aosUtFailed(stream, &result);
302 327
  }
303 328

  
304
  reset_DW1000();
305

  
306
  chprintf(stream, "initialise instance for DW1000 \n");
307
  aosThdSleep(1);
308

  
309
  int x_init = instance_init((DW1000Driver*) ut->data) ;
329
  /*! Blinking TX and RX LED simultenously for 5 times */
330
  chprintf(stream, "blinking TX and RX LEDs simultenously for 5 times \n");
331
  for(int i =0; i< 5; i++){
332
    uint8_t mode = 3;
333
    uint32_t reg ;
334

  
335
    // Set up for LED output.
336
    reg = dwt_read32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET); // Hardcoded = 0xDE001400
337
    reg &= ~(GPIO_MSGP2_MASK | GPIO_MSGP3_MASK);
338
    reg |= (GPIO_PIN2_RXLED | GPIO_PIN3_TXLED);
339
    dwt_write32bitoffsetreg(GPIO_CTRL_ID, GPIO_MODE_OFFSET, reg);
340

  
341
    // Enable LP Oscillator to run from counter and turn on de-bounce clock.
342
    reg = dwt_read32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET);      // hard-coded = 0xF0B40200
343
    reg |= (PMSC_CTRL0_GPDCE | PMSC_CTRL0_KHZCLEN);
344
    dwt_write32bitoffsetreg(PMSC_ID, PMSC_CTRL0_OFFSET, reg);
345

  
346
    // Enable LEDs to blink and set default blink time.
347
    reg = PMSC_LEDC_BLNKEN | PMSC_LEDC_BLINK_TIME_DEF;
348
    // Make LEDs blink once if requested.
349
    if (mode & DWT_LEDS_INIT_BLINK)
350
    {
351
      reg |= PMSC_LEDC_BLINK_NOW_ALL;
352
    }
353
    dwt_write32bitoffsetreg(PMSC_ID, PMSC_LEDC_OFFSET, reg);
354
    // Clear force blink bits if needed.
355
    if(mode & DWT_LEDS_INIT_BLINK)
356
    {
357
      reg &= ~PMSC_LEDC_BLINK_NOW_ALL;
358
      dwt_write32bitoffsetreg(PMSC_ID, PMSC_LEDC_OFFSET, reg);
359
    }
360
    aosThdMSleep(500);
361
  }
310 362

  
311
  if (0 != x_init){
363
  /*! UT2: Initialization  of the DW1000 module */
364
  reset_DW1000();
365
  chprintf(stream, "initialise the instance for DW1000 \n");
366
  aosThdMSleep(100);
367
  int x_init = instance_init(h_dw1000data->dw1000d) ;
368
  if (x_init != 0){
312 369
    chprintf(stream, "init error with return value: %d \n", x_init);
313
    aosThdSleep(1);
314 370
  }
315 371
  else {
316
    chprintf(stream, "init success with return value: %d \n", x_init);
317
    aosThdSleep(1);
372
    chprintf(stream, "succeed init! \n");
318 373
  }
319

  
320
  /*! UT2: Initialization  result*/
374
  aosThdMSleep(100);
321 375
  if (x_init == 0){
322 376
    aosUtPassed(stream, &result);
323 377
  } else {
324 378
    aosUtFailed(stream, &result);
325 379
  }
326 380

  
327
  setHighSpeed_SPI(true, (DW1000Driver*) ut->data);
328

  
329
  chprintf(stream, "expected device ID (HS SPI): 0xDECA0130\n");
330
  actual_deviceId = instancereaddeviceid();
331
  chprintf(stream, "actual read ID: 0x%x\n", actual_deviceId);
332
  aosThdMSleep(1);
333

  
334
  /*! UT3: High speed SPI result*/
335
  if (actual_deviceId == DWT_DEVICE_ID){
381
  /*! UT3: High speed SPI Testing */
382
  setHighSpeed_SPI(true, h_dw1000data->dw1000d);
383
  chprintf(stream, "expected ID (HS SPI): 0xDECA0130\n");
384
  actual_devID = instancereaddeviceid();
385
  chprintf(stream, "Read ID (HS SPI): 0x%x\n", actual_devID);
386
  aosThdMSleep(100);
387
  if (actual_devID == DWT_DEVICE_ID){
336 388
    aosUtPassed(stream, &result);
337 389
  } else {
338 390
    aosUtFailed(stream, &result);
339 391
  }
340 392

  
393
  /*! UT4: Configuration of UWB module
394
   * If all the five unit tests are passed, the module is ready to run.
395
   * Note that the interrupt IRQn should be tested separately.
396
   */
341 397
  port_EnableEXT_IRQ();
342 398
  reset_DW1000();
343

  
344 399
  chprintf(stream, "initialise the configuration for UWB application \n");
345 400
  aosThdSleep(1);
346

  
347
  int uwb_init = UWB_Init((DW1000Driver*) ut->data);
348

  
349
  if (0 != uwb_init){
401
  int uwb_init = UWB_Init(h_dw1000data->dw1000d);
402
  if (uwb_init != 0){
350 403
    chprintf(stream, "UWB config error with return value: %d \n", uwb_init);
351
    aosThdSleep(1);
352 404
  }
353 405
  else {
354
    chprintf(stream, "UWB config success with return value: %d \n", uwb_init);
355
    aosThdSleep(1);
406
    chprintf(stream, "succeed UWB config process \n", uwb_init);
356 407
  }
357

  
358
  /*! UT4: UWB configuration result
359
   * If all the four unit tests are passed, the module is ready to run.
360
   * Note that the interrupt IRQn should be tested separately.
361
   */
362 408
  if (uwb_init == 0){
363 409
    aosUtPassed(stream, &result);
364 410
  } else {
365 411
    aosUtFailed(stream, &result);
366 412
  }
367 413

  
368
  /************** End of UNIT_TEST_SNIPPETS_DW1000*****************/
414
  /************** End of UNIT_TEST_SNIPPETS_DW1000 *****************/
369 415

  
370 416
#else /* defined(UNIT_TEST_SNIPPETS_DW1000) */
371 417

  
372

  
373 418
  /*! RUN THE STATE MACHINE DEMO APP (RTLS) */
374

  
375 419
  chprintf(stream, "initialise the State Machine \n");
376 420
  aosThdSleep(2);
377 421

  
378 422
  /* Initialize UWB system with user defined configuration  */
379
  int uwb_init = UWB_Init((DW1000Driver*) ut->data);
423
  int uwb_init = UWB_Init(h_dw1000data->dw1000d);
380 424

  
381
  if (0 != uwb_init){
425
  if (uwb_init != 0){
382 426
    chprintf(stream, "error in UWB config with return value: %d \n", uwb_init);
383 427
  }
384 428
  else {
385 429
    chprintf(stream, "succeed the init of UWB config \n");
386 430
  }
387 431
  aosThdSleep(1);
388

  
389 432
  chprintf(stream, "running the RTLS demo application ... \n");
390
  aosThdSleep(1);
391 433

  
392 434
  /*! Run the localization system demo app as a thread */
393 435
  while(1){
394 436
    instance_run();
395 437
//    aosThdUSleep(10);
438
//    aosThdMSleep(1);
396 439
  }
397 440

  
398 441
#endif  /* defined(UNIT_TEST_SNIPPETS_DW1000) */

Also available in: Unified diff