Raspberry Pi Sensors

Raspberry Pi boards offer an easy way to connect different sensors and control devices. With specially designed I/O pins available to program them by developers the amount of possible implementations growth year by year. Any I/O General Purpose Input-Output Ports (GPIO) can be set as Digital Input or Output. The board contains two PWM pins which can be used as output analogue signals. Some of the interface libraries, such as pigpio or wiringPi, support this feature. It is also the way the Raspberry Pi outputs analogue audio.

Touch Sensors

Button

A pushbutton is an electromechanical sensor that connects or disconnects two points in a circuit when the force is applied. Button output discrete value is either HIGH or LOW.

A microswitch, also called a miniature snap-action switch, is an electromechanical sensor that requires a very little physical force and uses tipping-point mechanism. Microswitch has three pins, two of which are connected by default. When the force is applied, the first connection breaks and one of the pins is connected to the third pin.

The most common use of a push button is as an input device. Both force solutions can be used as simple object detectors, or as end switches in the industrial devices.

 title
Figure 1: A push button[1] and a microswitch [2].
 title
Figure 2: Schematics of Raspberry Pi and a push button.

To proper work with the button, the GPIO4 must be configured as an digital input. Pressing the push button connects the GPIO4 pin to the boards GND. On Raspberry Pi GPIO input pins are normally pulled up to 3.3 V. When the button is pressed, and GPIO4 is read using GPIO.input, it will return the FALSE result. Each GPIO pin can be configured to use internal pull-up or pull-down resistors. Using a GPIO pin as an input, these resistors can be configured using the optional pull_up_down parameter in the GPIO.setup. If this parameter is omitted, resistors will not be activated. In this case, the input may floating giving unpredicted results during reading it. If the GPIO pin is set to GPIO.UD_UP, the pull-up resistor is enabled; if it is set to GPIO.PUD_DOWN, the pull-down resistor is enabled.

An example code:

#Python code for Raspberry Pi
 
import RPi.GPIO as GPIO
import time
 
GPIO.setmode(GPIO.BCM)
s_pin = 7 #Select the GPIO4 pin
 
#Set the GPIO4 port to input mode
GPIO.setup(s_pin, GPIO.IN, pull_up_down=GPIO.PUD_UP) 
 
while True:
    input_state = GPIO.input(s_pin)
    if input_state == False:
        print('Button Pressed')
        time.sleep(0.2)

Running the code as superuser shows:

pi@raspberrypi ~ $ sudo python switch.py
Button Pressed
Button Pressed
Button Pressed
Button Pressed
Force Sensor

A force sensor predictably changes resistance, depending on the applied force to its surface. Force-sensing resistors are manufactured in different shapes and sizes, and they can measure not only direct force but also the tension, compression, torsion and other types of mechanical forces. The voltage is measured by applying and measuring constant voltage to the sensor.

Force sensors are used as control buttons or to determine weight.

 title
Figure 3: 0.5 inch force sensing resistor (FSR) [3].
 title
Figure 4: Raspberry Pi and Force Sensitive Resistor circuit schematics.

An example code:

#Python code for Raspberry Pi
 
import RPi.GPIO as GPIO
import time
 
GPIO.setmode(GPIO.BCM)
 
a_pin = 7   #Select the GPIO4 pin
b_pin = 29  #Select the GPIO5 pin
 
def discharge():
    GPIO.setup(a_pin, GPIO.IN)
    GPIO.setup(b_pin, GPIO.OUT)
    GPIO.output(b_pin, False)
    time.sleep(0.005)
 
def charge_time():
    GPIO.setup(b_pin, GPIO.IN)
    GPIO.setup(a_pin, GPIO.OUT)
    count = 0
    GPIO.output(a_pin, True)
    while not GPIO.input(b_pin):
        count = count + 1
    return count
 
def analog_read():
    discharge()
    return charge_time()
 
while True:
    print(analog_read())
    time.sleep(1)

Running the code as superuser shows:

$ sudo python pot_step.py
10
12
10
10
16
23
43
53
67
72
86
105
123
143
170

The idea of how to read the force sensor changing value is called step response. It works by checking how the circuit responds to the step change when an output is switched from low to high. Raspberry Pi isn't equipped with an ADC converter. So it is impossible to read voltage directly. However, it can be measured how long the capacitor will fill with the charge to the extent that it gets voltage above 1.65 V or so that constitutes a high digital input. The speed at which the capacitor fills with charge depends on the value of the variable resistor (Rt). The lower the resistance, the faster the capacitor fills with charge, and the voltage rises. To get the proper value, the circuit must empty the capacitor each time before the reading starts. In the schematic the GPIO4 is used to charge the capacitor and GPIO5 is used to discharge the capacitor through the 10 kΩ resistor. Both resistors are used to make sure that there is no way too much current can flow as the capacitor is charged and discharged. To discharge it, connection GPIO4 is set to be an input, effectively disconnecting Rc and Rt from the circuit. Connection GPIO5 is then set to be an output and low. It is held there for 5 milliseconds, to empty the capacitor.

Capacitive Sensor

Capacitive sensors are a range of sensors that use capacitance to measure changes in the surrounding environment. A capacitive sensor consists of a capacitor that is charged with a certain amount of current until the threshold voltage. A human finger, liquids or other conductive or dielectric materials that touch the sensor, can influence a charge time and a voltage level in the sensor. Measuring charge time and a voltage level gives information about changes in the environment.

Capacitive sensors are used as input devices and can measure proximity, humidity, fluid level and other physical parameters or serve as an input for electronic device control.

 title
Figure 5: Digital capacitive touch sensor v2.0 switch module [4].
 title
Figure 6: Raspberry Pi and capacitive sensor schematics.
#Python code for Raspberry Pi
 
import time
import pigpio #http://abyz.co.uk/rpi/pigpio/python.html
RXD=15        #Define the RxD serial input port
 
pi = pigpio.pi()
if not pi.connected:
   exit(0)
 
pigpio.exceptions = False #Ignore error if already set as bit bang read.
pi.bb_serial_read_open(RXD, 9600) #Set baud rate here.
pigpio.exceptions = True
pi.bb_serial_invert(RXD, 1) #Invert line logic.
stop = time.time() + 60.0
while time.time() < stop:
  (count, data) = pi.bb_serial_read(RXD)
  if count:
    print(data)
  time.sleep(0.2)
 
pi.bb_serial_read_close(RXD)
 
pi.stop()

Proximity and Distance Sensors

Ultrasound Sensor

Ultrasound (ultrasonic) sensor measures the distance to objects by emitting ultrasound and measuring its returning time. The sensor consists of an ultrasonic emitter and receiver; sometimes, they are combined in a single device for emitting and receiving. Ultrasonic sensors can measure greater distances and cost less than infrared sensors, but are more imprecise and interfere which each other measurement if more than one is used. Simple sensors have trigger pin and echo pin, when the trigger pin is set high for the small amount of time ultrasound is emitted and on echo pin, response time is measured. Ultrasonic sensors are used in car parking sensors and robots for proximity detection.

 title
Figure 7: Ultrasonic proximity sensor HC-SR04 [5].

Examples of IoT applications are robotic obstacle detection and room layout scanning.

 title
Figure 8: Raspberry Pi and ultrasound proximity sensor circuit.

An example code:

#Python code for Raspberry Pi
 
import RPi.GPIO as GPIO
import time
 
TRIG =  7  #Define a trigger pin GPIO4
ECHO = 29  #Define an echo pin GPIO5
 
print ("Distance Measurement In Progress")
 
GPIO.setup(TRIG, GPIO.OUT)     #Set the GPIO4 as trigger output port
GPIO.setup(ECHO,GPIO.IN)       #Set the GPIO5 pin as echo input
 
GPIO.output (TRIG,False)
 
print ("Waiting for Sensor to Settle")
time.sleep(2)
 
GPIO.output (TRIG, True)
time.sleep (0.00001)
GPIO.output (TRIG, False)
 
while GPIO.input(ECHO) == 0:
  pulse_start = time.time()
 
while GPIO.input(ECHO) == 1:
  pulse_end = time.time()
 
pulse_duration = pulse_end - pulse_start
distance = pulse_duration*17150
distance = round(distance,2)         #Calculating the distance
print ("Distance:", distance, "cm")

Running the code as superuser shows:

pi@raspberrypi > $ sudo python range_sensor.py
Distance Measurement To Settle
Distance: 23.54 cm
pi@raspberrypi > $
Motion Detector

The motion detector is a sensor that detects moving objects, most people. Motion detectors use different technologies, like passive infrared sensors, microwaves and Doppler effect, video cameras and previously mentioned ultrasonic and IR sensors. Passive IR sensors are the simplest motion detectors that sense people trough detecting IR radiation that is emitted through the skin. When the motion is detected, the output of a motion sensor is a digital HIGH/LOW signal.

Motion sensors are used for security purposes, automated light and door systems. As an example in IoT, the PIR motion sensor can be used to detect motion in security systems a house or any building.

 title
Figure 9: PIR motion sensor HC-SR501 [6].
 title
Figure 10: Raspberry Pi and PIR motion sensor circuit.

An example code:

#Python code for Raspberry Pi
 
pirPin = 7; //Passive Infrared (PIR) sensor output is connected to the GPIO4 pin
 
GPIO.setup(pirPin ,GPIO.IN)       #Set the GPIO5 pin as echo input
 
while 1:
  #Read the digital value of the PIR motion sensor GPIO4
  pirReading = GPIO.input(pirPin) 
  print (piReading)               #Print out
 
  if pirReading == True:          #Motion was detected
    print ('Motion Detected')
  time.sleep(10)
Gyroscope

A gyroscope is a sensor that measures the angular velocity. The sensor is made of the microelectromechanical system (MEMS) technology and is integrated into the chip. The output of the sensor can be either analogue or digital value of information, using I2C or SPI interface. Gyroscope microchips can vary in the number of axes they can measure. The available number of the axis is 1, 2 or 3 axes in the gyroscope. For gyroscopes with 1 or 2 axes, it is essential to determine which axis the gyroscope measures and to choose a device according to the project needs. A gyroscope is commonly used together with an accelerometer, to determine the orientation, position and velocity of the device precisely. Gyroscope sensors are used in aviation, navigation and motion control.

Gyroscope sensors are used in aviation, navigation and motion control.

 title
Figure 11: MPU 6050 GY-521 breakout board [7].
 title
Figure 12: Raspberry Pi and MPU 6050 GY-521 gyro breakout schematics.

The example code for the FXAS21002C sensor used in the breakout board:

#Python code for Raspberry Pi
#!/usr/bin/env python
 
from __future__ import division, print_function
from nxp_imu import IMU
import time
 
imu = IMU(gs=4, dps=2000, verbose=True)
header = 67
print('-'*header)
print("| {:17} | {:20} | {:20} |".format("Accels [g's]", " Magnet [uT]", "Gyros [dps]"))
print('-'*header)
for _ in range(10):
  a, m, g = imu.get()
  print('| {:>5.2f} {:>5.2f} {:>5.2f} | {:>6.1f} {:>6.1f} 
           {:>6.1f} | {:>6.1f} {:>6.1f} {:>6.1f} |'.format(
         a[0], a[1], a[2],
         m[0], m[1], m[2],
         g[0], g[1], g[2])
       )
  time.sleep(0.50)
print('-'*header)
print(' uT: micro Tesla')
print('  g: gravity')
print('dps: degrees per second')
print('')
Compass

A compass is a sensor, that can measure the orientation of the device to the magnetic field of the Earth. Solid state compass consists of the magnetometer and accelerometers in a single chip to precisely calculate the position of the device. Devices communicate through I2C or SPI interfaces and can return calculated heading, pitch and roll and raw accelerometer and magnetometer values. Compass is used in outdoor navigation for mobile devices, robots, quadcopters.

 title
Figure 13: Compass module HMC5883L [8].
 title
Figure 14: Raspberry Pi and Compass module HMC5883L schematics.

The example code:

1. Install i2c:
   sudo apt-get install i2c-tools
2. edit file /etc/modprobe.d/raspi-blacklist.conf 
       and comment out the line blacklist i2c-bcm2708
3. edit /etc/modules, and add the lines:
   i2c-bcm2708
   i2c-dev
4. Allow i2c access from users other than root, 
       by creating the file /etc/udev/rules.d/99-i2c.rules with this line:
   SUBSYSTEM=="i2c-dev", MODE="0666"
5. Reboot the Pi. When it goes up again, type:
   ls /dev/i2c*
On Pi (Model B, Revision 2 version, early 2013) it generates:
/dev/i2c-0 /dev/i2c-1
Optional: For python, install the smbus python library with:
1. apt-get install python-smbus
2. Install Python 3, can’t hurt, and i2clibraries needs it. 
        Just type sudo apt-get install python3
3. Test if the compass is detected, by typing:
   i2cdetect -y 1 (for Revision 1 Pis, replace 1 with 0).
4. Replace with 0 for Revision 1 Raspberry Pis and with 
        1 for Revision 2 boards. This is the output:
   0 1 2 3 4 5 6 7 8 9 a b c d e f
   00: -- -- -- -- -- -- -- -- -- -- -- -- --
   10: -- -- -- -- -- -- -- -- -- -- -- -- -- -- 1e --
   20: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
   30: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
   40: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
   50: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
   60: -- -- -- -- -- -- -- -- -- -- -- -- -- -- -- --
   70: -- -- -- -- -- -- -- --

Tip: if you don’t see it, it’s because you haven’t welded the pins to the sensor. Just press with your finger. Or weld it.
1. Add the quick2wire code. Pull from git:
   git clone https://github.com/quick2wire/quick2wire-python-api.git.
   On /etc/profile, add: export QUICK2WIRE_API_HOME=/home/pi/quick2wire-python-api
2. export PYTHONPATH=$PYTHONPATH:$QUICK2WIRE_API_HOME
   Add i2clibraries. Pull from git:git 
   clone https://bitbucket.org/thinkbowl/i2clibraries.git

Environment Sensors

Temperature Sensor

A temperature sensor is a device that is used to determine the temperature of the surrounding environment. Most temperature sensors work on the principle that the resistance of the material is changed depending on its temperature. The most common temperature sensors are:

  • thermocouple – consists of two junctions of dissimilar metals,
  • thermistor – includes the temperature-dependent ceramic resistor,
  • resistive temperature detector – is made of a pure metal coil.

The main difference between sensors is the measured temperature range, precision and response time. Temperature sensor usually outputs the analogue value, but some existing sensors have a digital interface [9].

The temperature sensors most commonly are used in environmental monitoring devices and thermoelectric switches. In IoT applications, the sensor can be used for greenhouse temperature monitoring, warehouse temperature monitoring to avoid frozen fire suppression systems and tracking temperature of the soil, water and plants.

 title
Figure 15: Thermistor sensor [10].
 title
Figure 16: Raspberry Pi and thermistor circuit.

An example code is similar to the Raspberry Pi force sensor sample. The thermistor changes its resistance depends on the environment temperature, and it can be read using similar code:

#Python code for Raspberry Pi
 
import RPi.GPIO as GPIO
import time
 
GPIO.setmode(GPIO.BCM)
 
a_pin = 7   #Select the GPIO4 pin
b_pin = 29  #Select the GPIO5 pin
 
def discharge():
    GPIO.setup(a_pin, GPIO.IN)
    GPIO.setup(b_pin, GPIO.OUT)
    GPIO.output(b_pin, False)
    time.sleep(0.005)
 
def charge_time():
    GPIO.setup(b_pin, GPIO.IN)
    GPIO.setup(a_pin, GPIO.OUT)
    count = 0
    GPIO.output(a_pin, True)
    while not GPIO.input(b_pin):
        count = count + 1
    return count
 
def analog_read():
    discharge()
    return charge_time()
 
while True:
    print(analog_read())
    time.sleep(1)
Humidity Sensor

A humidity sensor (hygrometer) is a sensor that detects the amount of water or water vapour in the environment. The most common principle of the air humidity sensors is the change of capacitance or resistance of materials that absorb the moisture from the environment. Soil humidity sensors measure the resistance between the two electrodes. The resistance between electrodes is influenced by soluble salts and water amount in the soil. The output of a humidity sensor is usually an analogue signal value [11].

Example IoT applications are monitoring of humidor, greenhouse temperature and humidity, agricultural environment and art gallery and museum environment.

 title
Figure 17: DHT11 temperature and humidity sensor breakout [12].
 title
Figure 18: Raspberry Pi and humidity sensor schematics.

An example code [13]:

1. Enter this at the command prompt to download the library:
   git clone https://github.com/adafruit/Adafruit_Python_DHT.git

2. Change directories with: 
   cd Adafruit_Python_DHT

3. Now enter this: 
   sudo apt-get install build-essential python-dev

4. Then install the library with: 
   sudo python setup.py install
#Python code for Raspberry Pi
#!/usr/bin/python
 
import sys
import Adafruit_DHT
 
while True:
    humidity, temperature = Adafruit_DHT.read_retry(11, 7) #Read GPIO4 Pin 7
    print ('Temp: {0:0.1f} C  Humidity: {1:0.1f} %'.format(temperature, humidity))
Sound Sensor

A sound sensor is a sensor that detects vibrations in a gas, liquid or solid environments. At first, the sound wave pressure makes mechanical vibrations, who transfers to changes in capacitance, electromagnetic induction, light modulation or piezoelectric generation to create an electric signal. The electrical signal is then amplified to the required output levels. Sound sensors, can be used to record sound, detect noise and its level.

Sound sensors are used in drone detection, gunshot alert, seismic detection and vault safety alarm.

 title
Figure 19: Digital sound detector sensor module [14].
 title
Figure 20: Raspberry Pi and sound sensor schematics.

An example code:

#Python code for Raspberry Pi
 
import time
import RPi.GPIO as GPIO
from qhue import Bridge
 
GPIO.setmode(GPIO.BCM) #Use board pin numbers
pin = 7                #Define GPIO4 as Input
GPIO.setup(pin, GPIO.IN) 
 
def callback (pin)
  if GPIO.input (pin)
    print ("Sound detected!")
  else:
    print ("Sound detected!")
  #Activate when pin changed its state
  GPIO.add_event_detect(pin,GPIO_BOTH, bouncetime=300) 
  #Assign function to GPIO PIN run it on changes
  GPIO.add_event_callback(pin,callback)                
 
#Infinite loop
while True:
 time.sleep(1)  
Chemical/Smoke and Gas Sensor

Gas sensors are a sensor group, that can detect and measure a concentration of certain gasses in the air. The working principle of electrochemical sensors is to absorb the gas and to create current from an electrochemical reaction. For process acceleration, a heating element can be used. For each type of gas, different kind of sensor needs to be used. Multiple different types of gas sensors can be combined in a single device as well. The single gas sensor output is an analogue signal, but devices with multiple sensors used to have a digital interface.

Gas sensors are used for safety devices, to control air quality and for manufacturing equipment. Examples of IoT applications are air quality control management in smart buildings and smart cities or toxic gas detection in sewers and underground mines.

 title
Figure 21: MQ2 gas sensor [15].
 title
Figure 22: Raspberry Pi and MQ2 gas sensor schematics.

An example code:

#Python code for Raspberry Pi

1. git clone https://github.com/tutRPi/Raspberry-Pi-Gas-Sensor-MQ
2. cd Raspberry-Pi-Gas-Sensor-MQ
3. sudo python example.py
#Python code for Raspberry Pi
#!/usr/bin/env python
 
import PCF8591 as ADC
import RPi.GPIO as GPIO
import time
import math
 
DO   = 17
Buzz = 18
GPIO.setmode(GPIO.BCM)
 
def setup():
  ADC.setup(0x48)
  GPIO.setup  (DO, GPIO.IN)
  GPIO.setup  (Buzz, GPIO.OUT)
  GPIO.output (Buzz, 1)
 
def Print(x):
  if x == 1:
    print ('')
    print ('   *********')
    print ('   * Safe~ *')
    print ('   *********')
    print ('')
    if x == 0:
      print ('')
      print ('   ***************')
      print ('   * Danger Gas! *')
      print ('   ***************')
      print ('')
 
def loop():
  status = 1
  count = 0
  while True:
    print (ADC.read(0))
 
    tmp = GPIO.input(DO);
    if tmp != status:
      print(tmp)
      status = tmp
      if status == 0:
        count += 1
        if count % 2 == 0:
          GPIO.output(Buzz, 1)
        else:
          GPIO.output(Buzz, 0)
      else:
	GPIO.output(Buzz, 1)
	count = 0
 
time.sleep(0.2)
 
def destroy():
  GPIO.output(Buzz, 1)
  GPIO.cleanup()
 
if __name__ == '__main__':
  try:
    setup()
    loop()
    except KeyboardInterrupt: 
    destroy()

Other Sensors

Global Positioning System

A GPS receiver is a device, that can receive information from a global navigation satellite system and calculate its position on the Earth. GPS receiver uses a constellation of satellites and ground stations to compute position and time almost anywhere on the Earth. GPS receivers are used for navigation only in the outdoor area because it needs to receive signals from the satellites. The precision of the GPS location can vary.

A GPS receiver is used for device location tracking. Real world applications might be pet, kid or personal belonging location tracking.

 title
Figure 23: LS20031 GPS receiver [16].
 title
Figure 24: Raspberry Pi and LS20031 GPS receiver schematics.

The example code:

#Python code for Raspberry Pi
#!/usr/bin/python
 
import os
import pygame, sys
from pygame.locals import *
import serial
 
#Initialise serial port on /ttyUSB0
ser = serial.Serial('/dev/ttyUSB0',4800,timeout = None)
#Set font size MAX 100
fontsize = 50
 
#Calculate window size
width = fontsize * 17
height = fontsize + 10
 
#Initilaise pygame
pygame.init()
windowSurfaceObj = pygame.display.set_mode((width,height),1,16)
fontObj = pygame.font.Font('freesansbold.ttf',fontsize)
pygame.display.set_caption('GPS Location')
redColor = pygame.Color(255,0,0)
greenColor = pygame.Color(0,255,0)
yellowColor = pygame.Color(255,255,0)
blackColor = pygame.Color(0,0,0)
 
fix = 1
color = redColor
x = 0
while x == 0:
  gps = ser.readline()
  #Print (all NMEA strings)
  print (gps)
  #Check gps fix status
  if gps[1:6] == "GPGSA":
    fix = int(gps[9:10])
    if fix == 2:
      color = yellowColor
    if fix == 3:
      color = greenColor
   #Print (time, lat and long from #GPGGA string)
    if gps[1 : 6] == "GPGGA":
      #Clear window
      pygame.draw.rect(windowSurfaceObj,blackColor,Rect(0,0,width,height))
      pygame.display.update(pygame.Rect(0,0,width,height))
      #Get time
      time = gps[7:9] + ":" + gps[9:11] + ":" + gps[11:13]
      #If 2 or 3D fix get lat and long
      if fix > 1:
        lat = " " + gps[18:20] + "." + gps[20:22] + "." + gps[23:27] + gps[28:29]
        lon = " " + gps[30:33] + "." + gps[33:35] + "." + gps[36:40] + gps[41:42]
      #If no fix
      else:
        lat = " No Valid Data "
        lon = " "
      #Print new values   
      msgSurfaceObj = fontObj.render(str(time), False,color)   
      msgRectobj = msgSurfaceObj.get_rect()
      msgRectobj.topleft =(2,0)
      windowSurfaceObj.blit(msgSurfaceObj, msgRectobj)
 
      msgSurfaceObj = fontObj.render(str(lat), False,color)   
      msgRectobj = msgSurfaceObj.get_rect()
      msgRectobj.topleft =(210,0)
      windowSurfaceObj.blit(msgSurfaceObj, msgRectobj)
 
      msgSurfaceObj = fontObj.render(str(lon), False,color)   
      msgRectobj = msgSurfaceObj.get_rect()
      msgRectobj.topleft =(495,0)
      windowSurfaceObj.blit(msgSurfaceObj, msgRectobj)
      pygame.display.update(pygame.Rect(0,0,width,height))
      fix = 1
      color = redColor
 
   #Check for ESC key pressed, or GPS Location window closed, to quit
   for event in pygame.event.get():
     if event.type == QUIT or (event.type == KEYDOWN and event.key == K_ESCAPE):
       pygame.quit()
       sys.exit()
}
en/iot-open/getting_familiar_with_your_hardware_rtu_itmo_sut/raspberrypi_rpi/sensors_and_sensing.txt · Last modified: 2020/07/27 09:00 by 127.0.0.1
CC Attribution-Share Alike 4.0 International
www.chimeric.de Valid CSS Driven by DokuWiki do yourself a favour and use a real browser - get firefox!! Recent changes RSS feed Valid XHTML 1.0