PsiSwarm Library  0.8
All Classes Files Functions Macros Pages
sensors.cpp
1 /* University of York Robotics Laboratory PsiSwarm Library: Sensor Functions Source File
2  *
3  * Copyright 2016 University of York
4  *
5  * Licensed under the Apache License, Version 2.0 (the "License"); you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at http://www.apache.org/licenses/LICENSE-2.0
7  * Unless required by applicable law or agreed to in writing, software distributed under the License is distributed on an "AS IS" BASIS
8  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
9  * See the License for the specific language governing permissions and limitations under the License.
10  *
11  * File: sensors.cpp
12  *
13  * (C) Dept. Electronics & Computer Science, University of York
14  * James Hilder, Alan Millard, Alexander Horsfield, Homero Elizondo, Jon Timmis
15  *
16  * PsiSwarm Library Version: 0.8
17  *
18  * October 2016
19  *
20  *
21  */
22 
23 #include "psiswarm.h"
24 
26 // Ultrasonic Sensor (SRF02) Functions
28 
29 // The ultrasonic sensor needs a start command to be sent: this is done by calling update_ultrasonic_measure().
30 // It can be set to automatically refresh at 10Hz by called enable_ultrasonic_ticker and disable with disabled_ultrasonic_ticker
31 
33 {
34  ultrasonic_ticker.attach_us(this,&Sensors::update_ultrasonic_measure,100000);
35 }
36 
38 {
39  ultrasonic_ticker.detach();
40 }
41 
43 {
44  if(waiting_for_ultrasonic == 0) {
45  waiting_for_ultrasonic = 1;
46  if(has_ultrasonic_sensor) {
47  char command[2];
48  command[0] = 0x00; // Set the command register
49  command[1] = 0x51; // Get result is centimeters
50  primary_i2c.write(ULTRASONIC_ADDRESS, command, 2); // Send the command to start a ranging burst
51  }
52  ultrasonic_timeout.attach_us(this,&Sensors::IF_read_ultrasonic_measure,70000);
53  } else {
54  psi.debug("WARNING: Ultrasonic sensor called too frequently.\n");
55  }
56 }
57 
58 void Sensors::IF_read_ultrasonic_measure()
59 {
60  if(has_ultrasonic_sensor) {
61  char command[1];
62  char result[2];
63  command[0] = 0x02; // The start address of measure result
64  primary_i2c.write(ULTRASONIC_ADDRESS, command, 1, 1); // Send address to read a measure
65  primary_i2c.read(ULTRASONIC_ADDRESS, result, 2); // Read two byte of measure
66  ultrasonic_distance = (result[0]<<8)+result[1];
67  } else ultrasonic_distance = 0;
68  ultrasonic_distance_updated = 1;
69  waiting_for_ultrasonic = 0;
70  //psi.debug("US:%d cm\n",ultrasonic_distance);
71 }
72 
74 // Additional Sensing Functions
76 
78 {
79  if(has_temperature_sensor)return i2c_setup.IF_read_from_temperature_sensor();
80  return 0;
81 }
82 
84 // Voltage Sensing Functions
86 
88 {
89  float raw_value = vin_battery.read();
90  return raw_value * 4.95;
91 }
92 
94 {
95  // Device uses a INA211 current sense monitor measuring voltage drop across a 2mOhm resistor
96  // Device gain = 500
97  float raw_value = vin_current.read();
98  return raw_value * 3.3;
99 }
100 
102 {
103  float raw_value = vin_dc.read();
104  return raw_value * 6.6;
105 }
106 
108 // IR Sensor Functions
110 
111 // Estimates the distance to an obstacle from one of the IR sensors, defined by index (range 0-7).
112 // The value is converted to an approximate distance in millimetres, or 100.0 if no obstacle found.
113 // NB This function is preserved for code-compatability and cases where only a single reading is needed
114 // In many cases it is preferable to call store_reflected_ir_distances() to save all 8 values then read using get_reflected_ir_distance()
115 float Sensors::read_reflected_ir_distance ( char index )
116 {
117  // Sanity check
118  if(index>7) return 0.0;
119 
120  //1. Read the ADC value without IR emitter on; store in the background_ir_values[] array
121  background_ir_values [index] = i2c_setup.IF_read_IR_adc_value(1, index );
122 
123  //2. Enable the relevant IR emitter by turning on its pulse output
124  switch(index) {
125  case 0:
126  case 1:
127  case 6:
128  case 7:
129  i2c_setup.IF_set_IR_emitter_output(0, 1);
130  break;
131  case 2:
132  case 3:
133  case 4:
134  case 5:
135  i2c_setup.IF_set_IR_emitter_output(1, 1);
136  break;
137  }
138  wait_us(ir_pulse_delay);
139 
140  //3. Read the ADC value now IR emitter is on; store in the illuminated_ir_values[] array
141  illuminated_ir_values [index] = i2c_setup.IF_read_IR_adc_value (1, index );
142 
143  //4. Turn off IR emitter
144  switch(index) {
145  case 0:
146  case 1:
147  case 6:
148  case 7:
149  i2c_setup.IF_set_IR_emitter_output(0, 0);
150  break;
151  case 2:
152  case 3:
153  case 4:
154  case 5:
155  i2c_setup.IF_set_IR_emitter_output(1, 0);
156  break;
157  }
158 
159  //5. Estimate distance based on 2 values using calculate_reflected_distances(); store in reflected_ir_distances()
160  reflected_ir_distances [index] = calculate_reflected_distance( background_ir_values [index], illuminated_ir_values [index]);
161  ir_values_stored = 1;
162  return reflected_ir_distances [index];
163 }
164 
165 
166 // Returns the stored value of the reflected obstacle based on last call of either read_reflected_ir_distance or store_reflected_distances
167 float Sensors::get_reflected_ir_distance ( char index )
168 {
169  // Sanity check: check range of index and that values have been stored
170  if (index>7 || ir_values_stored == 0) return 0.0;
171  return reflected_ir_distances[index];
172 }
173 
174 // Returns the stored value of the non-illuminated sensor based on last call of store_background_raw_ir_values
175 unsigned short Sensors::get_background_raw_ir_value ( char index )
176 {
177  // Sanity check: check range of index and that values have been stored
178  if (index>7 || ir_values_stored == 0) return 0.0;
179  return background_ir_values[index];
180 }
181 
182 // Returns the stored value of the illuminated sensor based on last call of store_illuminated_raw_ir_values
183 unsigned short Sensors::get_illuminated_raw_ir_value ( char index )
184 {
185  // Sanity check: check range of index and that values have been stored
186  if (index>7 || ir_values_stored == 0) return 0.0;
187  return illuminated_ir_values[index];
188 }
189 
190 // Stores the reflected distances for all 8 IR sensors
191 void Sensors::store_reflected_ir_distances ( void )
192 {
193  store_ir_values();
194  for(int i=0; i<8; i++) {
195  reflected_ir_distances [i] = calculate_reflected_distance( background_ir_values [i], illuminated_ir_values [i]);
196  }
197 }
198 
199 // Stores the background and illuminated values for all 8 IR sensors
201 {
204 }
205 
206 // Stores the raw ADC values for all 8 IR sensors without enabling IR emitters
208 {
209  ir_values_stored = 1;
210  for(int i=0; i<8; i++) {
211  background_ir_values [i] = i2c_setup.IF_read_IR_adc_value(1,i);
212  }
213 }
214 
215 // Stores the raw ADC values for all 8 IR sensors with a 500us emitter pulse
217 {
218  //1. Enable the front IR emitters and store the values
219  i2c_setup.IF_set_IR_emitter_output(0, 1);
220  wait_us(ir_pulse_delay);
221  illuminated_ir_values [0] = i2c_setup.IF_read_IR_adc_value(1,0);
222  illuminated_ir_values [1] = i2c_setup.IF_read_IR_adc_value(1,1);
223  illuminated_ir_values [6] = i2c_setup.IF_read_IR_adc_value(1,6);
224  illuminated_ir_values [7] = i2c_setup.IF_read_IR_adc_value(1,7);
225  i2c_setup.IF_set_IR_emitter_output(0, 0);
226 
227  //2. Enable the rear+side IR emitters and store the values
228  i2c_setup.IF_set_IR_emitter_output(1, 1);
229  wait_us(ir_pulse_delay);
230  illuminated_ir_values [2] = i2c_setup.IF_read_IR_adc_value(1,2);
231  illuminated_ir_values [3] = i2c_setup.IF_read_IR_adc_value(1,3);
232  illuminated_ir_values [4] = i2c_setup.IF_read_IR_adc_value(1,4);
233  illuminated_ir_values [5] = i2c_setup.IF_read_IR_adc_value(1,5);
234  i2c_setup.IF_set_IR_emitter_output(1, 0);
235 }
236 
237 // Converts a background and illuminated value into a distance
238 float Sensors::calculate_reflected_distance ( unsigned short background_value, unsigned short illuminated_value )
239 {
240  float approximate_distance = 4000 + background_value - illuminated_value;
241  if(approximate_distance < 0) approximate_distance = 0;
242 
243  // Very approximate: root value, divide by 2, approx distance in mm
244  approximate_distance = sqrt (approximate_distance) / 2.0;
245 
246  // Then add adjustment value if value >27
247  if(approximate_distance > 27) {
248  float shift = pow(approximate_distance - 27,3);
249  approximate_distance += shift;
250  }
251  if(approximate_distance > 90) approximate_distance = 100.0;
252  return approximate_distance;
253 }
254 
255 // Returns the illuminated raw sensor value for the IR sensor defined by index (range 0-7); turns on the emitters for a 500us pulse
256 unsigned short Sensors::read_illuminated_raw_ir_value ( char index )
257 {
258  //This function reads the IR strength when illuminated - used for PC system debugging purposes
259  //1. Enable the relevant IR emitter by turning on its pulse output
260  switch(index) {
261  case 0:
262  case 1:
263  case 6:
264  case 7:
265  i2c_setup.IF_set_IR_emitter_output(0, 1);
266  break;
267  case 2:
268  case 3:
269  case 4:
270  case 5:
271  i2c_setup.IF_set_IR_emitter_output(1, 1);
272  break;
273  }
274  wait_us(ir_pulse_delay);
275  //2. Read the ADC value now IR emitter is on
276  unsigned short strong_value = i2c_setup.IF_read_IR_adc_value( 1,index );
277  //3. Turn off IR emitter
278  switch(index) {
279  case 0:
280  case 1:
281  case 6:
282  case 7:
283  i2c_setup.IF_set_IR_emitter_output(0, 0);
284  break;
285  case 2:
286  case 3:
287  case 4:
288  case 5:
289  i2c_setup.IF_set_IR_emitter_output(1, 0);
290  break;
291  }
292  return strong_value;
293 }
294 
295 // Base IR sensor functions
296 
297 
298 // Returns the stored value of the non-illuminated sensor based on last call of store_background_base_ir_values
299 unsigned short Sensors::get_background_base_ir_value ( char index )
300 {
301  // Sanity check: check range of index and that values have been stored
302  if (index>4 || base_ir_values_stored == 0) return 0.0;
303  return background_base_ir_values[index];
304 }
305 
306 // Returns the stored value of the illuminated sensor based on last call of store_illuminated_base_ir_values
307 unsigned short Sensors::get_illuminated_base_ir_value ( char index )
308 {
309  // Sanity check: check range of index and that values have been stored
310  if (index>4 || base_ir_values_stored == 0) return 0.0;
311  return illuminated_base_ir_values[index];
312 }
313 
314 // Stores the reflected distances for all 5 base IR sensors
316 {
319  //for(int i=0;i<5;i++){
320  // reflected_ir_distances [i] = calculate_reflected_distance( background_base_ir_values [i], illuminated_base_ir_values [i]);
321  //}
322 }
323 
324 // Stores the raw ADC values for all 5 base IR sensors without enabling IR emitters
326 {
327  base_ir_values_stored = 1;
328  for(int i=0; i<5; i++) {
329  background_base_ir_values [i] = i2c_setup.IF_read_IR_adc_value(2,i);
330  }
331 }
332 
333 // Stores the raw ADC values for all 5 base IR sensors with a 500us emitter pulse
335 {
336  //1. Enable the base IR emitters and store the values
337  i2c_setup.IF_set_IR_emitter_output(2, 1);
338  wait_us(base_ir_pulse_delay);
339  for(int i=0; i<5; i++) {
340  illuminated_base_ir_values [i] = i2c_setup.IF_read_IR_adc_value(2,i);
341  }
342 
343  i2c_setup.IF_set_IR_emitter_output(2, 0);
344 }
345 
346 // Routine to store detected line position in a similar format to the used on 3Pi\m3Pi\PiSwarm
347 void Sensors::store_line_position ( )
348 {
349  // Store background and reflected base IR values
351  int h_value[5];
352  int line_threshold = 1000;
353  int line_threshold_hi = 2000;
354  char count = 0;
355  line_found = 0;
356  line_position = 0;
357  for(int i=0; i<5; i++) {
360  if(h_value[i] < line_threshold) count++;
361  }
362  if(count == 1) {
363  line_found = 1;
364  if(h_value[0] < line_threshold) {
365  line_position = -1;
366  if(h_value[1] < line_threshold_hi) line_position = -0.8;
367  }
368 
369  if (h_value[1] < line_threshold) {
370  line_position = -0.5 + (0.00005 * h_value[0]) - (0.0001 * h_value[2]);;
371  }
372  if(h_value[2] < line_threshold) {
373  line_position = (0.00005 * h_value[1]) - (0.0001 * h_value[3]);
374  }
375  if(h_value[3] < line_threshold) {
376  line_position = 0.5 + (0.00005 * h_value[2]) - (0.0001 * h_value[4]);;
377  }
378  if(h_value[4] < line_threshold) {
379  line_position = 1;
380  if(h_value[3] < line_threshold_hi) line_position = 0.8;
381  }
382  }
383  if(count == 2) {
384  if(h_value[0] && h_value[1] < line_threshold) {
385  line_found = 1;
386  line_position = -0.6;
387  }
388 
389  if(h_value[1] && h_value[2] < line_threshold) {
390  line_found = 1;
391  line_position = -0.4;
392  }
393 
394  if(h_value[2] && h_value[3] < line_threshold) {
395  line_found = 1;
396  line_position = 0.4;
397  }
398 
399  if(h_value[3] && h_value[4] < line_threshold) {
400  line_found = 1;
401  line_position = 0.6;
402  }
403  }
404 }
405 
406 // Returns the subtraction of the background base IR value from the reflection based on last call of store_illuminated_base_ir_values
407 unsigned short Sensors::calculate_base_ir_value ( char index ){
408  // If the index is not in the correct range or the base IR values have not been stored, return zero
409  if (index>4 || base_ir_values_stored == 0) return 0.0;
410  // If the reflection value is greater than the background value, return the subtraction
411  if(illuminated_base_ir_values[index] > background_base_ir_values[index]){
412  return illuminated_base_ir_values[index] - background_base_ir_values[index];
413  //Otherwise return zero
414  } else {
415  return 0.0;
416  }
417 }
418 
419 // Returns the subtraction of the background side IR value from the reflection based on last call of store_illuminated_base_ir_values
420 unsigned short Sensors::calculate_side_ir_value ( char index ){
421  // If the index is not in the correct range or the base IR values have not been stored, return zero
422  if (index>7 || ir_values_stored == 0) return 0.0;
423  // If the reflection value is greater than the background value, return the subtraction
424  if(illuminated_ir_values[index] > background_ir_values[index]){
425  return illuminated_ir_values[index] - background_ir_values[index];
426  //Otherwise return zero
427  } else {
428  return 0.0;
429  }
430 }
431 
432 void Sensors::calibrate_base_ir_sensors (void)
433 {
434  short white_background[5];
435  short white_active[5];
436  short black_background[5];
437  short black_active[5];
438  for(int k=0; k<5; k++) {
439  white_background[k]=0;
440  black_background[k]=0;
441  white_active[k]=0;
442  black_active[k]=0;
443  }
444  pc.printf("Base IR Calibration\n");
445  display.clear_display();
446  display.write_string("Calibrating base");
447  display.set_position(1,0);
448  display.write_string("IR sensor");
449  wait(0.5);
450  display.clear_display();
451  display.write_string("Place robot on");
452  display.set_position(1,0);
453  display.write_string("white surface");
454  wait(3);
455  display.clear_display();
456  display.write_string("Calibrating base");
457  display.set_position(1,0);
458  display.write_string("IR sensor");
459  wait(0.5);
460  pc.printf("\nWhite Background Results:\n");
461 
462  for(int i=0; i<5; i++) {
463  wait(0.2);
465 
466  display.set_position(1,9);
467  display.write_string(".");
468  wait(0.2);
470  for(int k=0; k<5; k++) {
471  white_background[k]+= get_background_base_ir_value(k);
472  white_active[k] += get_illuminated_base_ir_value(k);
473  }
474  pc.printf("Sample %d 1: %04d-%04d 2: %04d-%04d 3: %04d-%04d 4: %04d-%04d 5: %04d-%04d\n", (i+1),
480  }
481  for(int k=0; k<5; k++) {
482  white_background[k]/=5;
483  white_active[k]/=5;
484  }
485  pc.printf("Mean results 1: %04d-%04d 2: %04d-%04d 3: %04d-%04d 4: %04d-%04d 5: %04d-%04d\n",
486  white_background[0], white_active[0],
487  white_background[1], white_active[1],
488  white_background[2], white_active[2],
489  white_background[3], white_active[3],
490  white_background[4], white_active[4]);
491 
492  display.clear_display();
493  display.write_string("Place robot on");
494  display.set_position(1,0);
495  display.write_string("black surface");
496  wait(3);
497 
498  display.clear_display();
499  display.write_string("Calibrating base");
500  display.set_position(1,0);
501  display.write_string("IR sensor");
502  wait(0.5);
503  pc.printf("\nBlack Background Results:\n");
504 
505  for(int i=0; i<5; i++) {
506  wait(0.2);
507 
509  display.set_position(1,9);
510  display.write_string(".");
511  wait(0.2);
513  for(int k=0; k<5; k++) {
514  black_background[k]+= get_background_base_ir_value(k);
515  black_active[k] += get_illuminated_base_ir_value(k);
516  }
517  pc.printf("Sample %d 1: %04d-%04d 2: %04d-%04d 3: %04d-%04d 4: %04d-%04d 5: %04d-%04d\n", (i+1),
523  }
524  for(int k=0; k<5; k++) {
525  black_background[k]/=5;
526  black_active[k]/=5;
527  }
528  pc.printf("Mean results 1: %04d-%04d 2: %04d-%04d 3: %04d-%04d 4: %04d-%04d 5: %04d-%04d\n",
529  black_background[0], black_active[0],
530  black_background[1], black_active[1],
531  black_background[2], black_active[2],
532  black_background[3], black_active[3],
533  black_background[4], black_active[4]);
534 
535 }
536 
537 
538 int Sensors::get_bearing_from_ir_array (unsigned short * ir_sensor_readings)
539 {
540  //out("Getting bearing from array: [%d][%d][%d][%d][%d][%d][%d][%d]\n",ir_sensor_readings[0],ir_sensor_readings[1],ir_sensor_readings[2],ir_sensor_readings[3],ir_sensor_readings[4],ir_sensor_readings[5],ir_sensor_readings[6],ir_sensor_readings[7]);
541 
542  float degrees_per_radian = 57.295779513;
543 
544  // sin(IR sensor angle) and cos(IR sensor angle) LUT, for all 8 sensors
545  float ir_sensor_sin[8] = {0.382683432, 0.923879533, 0.923879533, 0.382683432, -0.382683432, -0.923879533, -0.923879533, -0.382683432};
546  float ir_sensor_cos[8] = {0.923879533, 0.382683432, -0.382683432, -0.923879533, -0.923879533, -0.382683432, 0.382683432, 0.923879533};
547 
548  float sin_sum = 0;
549  float cos_sum = 0;
550 
551  for(int i = 0; i < 8; i++) {
552  // Use IR sensor reading to weight bearing vector
553  sin_sum += ir_sensor_sin[i] * ir_sensor_readings[i];
554  cos_sum += ir_sensor_cos[i] * ir_sensor_readings[i];
555  }
556 
557  float bearing = atan2(sin_sum, cos_sum); // Calculate vector towards IR light source
558  bearing *= degrees_per_radian; // Convert to degrees
559 
560  //out("Sin sum:%f Cos sum:%f Bearing:%f\n",sin_sum,cos_sum,bearing);
561 
562  return (int) bearing;
563 }
564 
void write_string(char *message)
Definition: display.cpp:131
void store_illuminated_raw_ir_values(void)
Definition: sensors.cpp:216
unsigned short read_illuminated_raw_ir_value(char index)
Definition: sensors.cpp:256
void store_background_raw_ir_values(void)
Definition: sensors.cpp:207
unsigned short calculate_side_ir_value(char index)
Definition: sensors.cpp:420
unsigned short calculate_base_ir_value(char index)
Definition: sensors.cpp:407
void set_position(char row, char column)
Definition: display.cpp:174
void clear_display(void)
Definition: display.cpp:230
void store_ir_values(void)
Definition: sensors.cpp:200
void update_ultrasonic_measure(void)
Definition: sensors.cpp:42
unsigned short get_background_base_ir_value(char index)
Definition: sensors.cpp:299
float get_dc_voltage(void)
Definition: sensors.cpp:101
float get_current(void)
Definition: sensors.cpp:93
void store_background_base_ir_values(void)
Definition: sensors.cpp:325
void enable_ultrasonic_ticker(void)
Definition: sensors.cpp:32
float get_battery_voltage(void)
Definition: sensors.cpp:87
unsigned short get_illuminated_base_ir_value(char index)
Definition: sensors.cpp:307
float get_temperature(void)
Definition: sensors.cpp:77
unsigned short get_background_raw_ir_value(char index)
Definition: sensors.cpp:175
void store_base_ir_values(void)
Definition: sensors.cpp:315
void store_illuminated_base_ir_values(void)
Definition: sensors.cpp:334
void debug(const char *format,...)
Definition: psiswarm.cpp:325
void disable_ultrasonic_ticker(void)
Definition: sensors.cpp:37
unsigned short get_illuminated_raw_ir_value(char index)
Definition: sensors.cpp:183