Skip to content

Commit

Permalink
bring develop to master for DexterOS 2.0 (#44)
Browse files Browse the repository at this point in the history
* Add Line Follower drivers and example

* Update dexter_i2c.py

Update dexter_i2c.py to be simpler and more universal by combining
functions.

* Update line_follower.py

Update line_follower.py for recent dexter_i2c.py update

* Feature/easy libraries (#35)

* Move Distance Sensor and Line Follower in here

* remove dependency on mock_package

* remove alias for read_sensors until we know if we need it (probably not)

* Feature/system wide mutex+ easydi_sensors library  (#36)

* Move Distance Sensor and Line Follower in here

* remove dependency on mock_package

* remove alias for read_sensors until we know if we need it (probably not)

* get easydi_sensors from DexterOS

* Check for overall mutex need

* Add systemwide mutex comment

* Add license header and description

* Add license header

* change year in license header

* split easydi_sensors into 3 components for systematic naming convention

* Remove copies of ifMutexAcquire and ifMutexRelease. Keep them in one file

* Be more strict in what we're pulling in from easy_mutex

* poll overall_mutex each time

* remove print statement (#37)

reconfig_bus() is now mutex protected

* feature - update documentation for the latest (#41)

* feature - configuring the environment for RTD

* feature - bulk changes to docs

* feature - add comment on how to build documentation

* feature - add part of the documentation

* feature - completing the documentation for easy sensors + tutorials

* feature - work on the tutorials + other stuff

* feature - fix the mutexes tutorial

* feature - change organization of documentation

* feature - remove an unnecessary section

* feature - show the right command for installing di-sensors

* feature - small changes

* feature - fix documentation & and missing parts

* feature - fix naming of the package

* Revert commit

* minor fixes to docs (#42)

* minor fixes to docs

* minor fixes to doc

* fix grammar

* rename safe_heading to heading_name and re-instate the parameter (#43)

* rename safe_heading to heading_name and re-instate the parameter

* rename from heading_name to convert_heading

* add punctuation

* fix - change name of method in library description section

* Remove references to line follower (#45)
  • Loading branch information
RobertLucian authored and CleoQc committed Apr 26, 2018
1 parent d6b6e69 commit 8c72f81
Show file tree
Hide file tree
Showing 32 changed files with 1,484 additions and 246 deletions.
26 changes: 26 additions & 0 deletions Python/Examples/EasyDistanceSensor.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
#!/usr/bin/env python
#
# https://www.dexterindustries.com
#
# Copyright (c) 2017 Dexter Industries
# Released under the MIT license (http://choosealicense.com/licenses/mit/).
# For more information see https://github.com/DexterInd/DI_Sensors/blob/master/LICENSE.md
#
# Python example program for the Dexter Industries Distance Sensor

from __future__ import print_function
from __future__ import division

# import the modules
from di_sensors.easy_distance_sensor import EasyDistanceSensor
from time import sleep

# instantiate the distance object
my_sensor = EasyDistanceSensor()

# and read the sensor iteratively
while True:
read_distance = my_sensor.read()
print("distance from object: {} mm".format(read_distance))

sleep(0.1)
51 changes: 51 additions & 0 deletions Python/Examples/EasyDistanceSensorMutexes.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,51 @@
#!/usr/bin/env python
#
# https://www.dexterindustries.com
#
# Copyright (c) 2017 Dexter Industries
# Released under the MIT license (http://choosealicense.com/licenses/mit/).
# For more information see https://github.com/DexterInd/DI_Sensors/blob/master/LICENSE.md
#
# Python example program for the Dexter Industries Temperature Humidity Pressure Sensor

from __future__ import print_function
from __future__ import division

# do the import stuff
from di_sensors.easy_distance_sensor import EasyDistanceSensor
from time import time, sleep
from threading import Thread, Event, get_ident

# instantiate the distance object
my_sensor = EasyDistanceSensor(use_mutex = True)
start_time = time()
runtime = 2.0
# create an event object for triggering the "shutdown" of each thread
stop_event = Event()

# target function for each thread
def readingSensor():
while not stop_event.is_set():
thread_id = get_ident()
distance = my_sensor.read()
print("Thread ID = {} with distance value = {}".format(thread_id, distance))
sleep(0.001)

# create an object for each thread
thread1 = Thread(target = readingSensor)
thread2 = Thread(target = readingSensor)

# and then start them
thread1.start()
thread2.start()

# let it run for [runtime] seconds
while time() - start_time <= runtime:
sleep(0.1)

# and then set the stop event variable
stop_event.set()

# and wait both threads to end
thread1.join()
thread2.join()
Original file line number Diff line number Diff line change
@@ -1,28 +1,28 @@
#!/usr/bin/env python
#
# https://www.dexterindustries.com
#
# Copyright (c) 2017 Dexter Industries
# Released under the MIT license (http://choosealicense.com/licenses/mit/).
# For more information see https://github.com/DexterInd/DI_Sensors/blob/master/LICENSE.md
#
# Python example program for the Dexter Industries Light Color Sensor

from __future__ import print_function
from __future__ import division

import time
from di_sensors.light_color_sensor import LightColorSensor

print("Example program for reading a Dexter Industries Light Color Sensor on an I2C port.")

lcs = LightColorSensor(led_state = True)

while True:
# Read the R, G, B, C color values
red, green, blue, clear = lcs.get_raw_colors()

# Print the values
print("Red: {:5.3f} Green: {:5.3f} Blue: {:5.3f} Clear: {:5.3f}".format(red, green, blue, clear))

time.sleep(0.02)
#!/usr/bin/env python
#
# https://www.dexterindustries.com
#
# Copyright (c) 2017 Dexter Industries
# Released under the MIT license (http://choosealicense.com/licenses/mit/).
# For more information see https://github.com/DexterInd/DI_Sensors/blob/master/LICENSE.md
#
# Python example program for the Dexter Industries Light Color Sensor

from __future__ import print_function
from __future__ import division

from time import sleep
from di_sensors.easy_light_color_sensor import EasyLightColorSensor

print("Example program for reading a Dexter Industries Light Color Sensor on an I2C port.")

my_lcs = EasyLightColorSensor(led_state = True)

while True:
# Read the R, G, B, C color values
red, green, blue, clear = my_lcs.safe_raw_colors()

# Print the values
print("Red: {:5.3f} Green: {:5.3f} Blue: {:5.3f} Clear: {:5.3f}".format(red, green, blue, clear))

sleep(0.02)
34 changes: 34 additions & 0 deletions Python/Examples/EasyTempHumPress.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,34 @@
#!/usr/bin/env python
#
# https://www.dexterindustries.com
#
# Copyright (c) 2017 Dexter Industries
# Released under the MIT license (http://choosealicense.com/licenses/mit/).
# For more information see https://github.com/DexterInd/DI_Sensors/blob/master/LICENSE.md
#
# Python example program for the Dexter Industries Temperature Humidity Pressure Sensor

from __future__ import print_function
from __future__ import division

from time import sleep
from di_sensors.easy_temp_hum_press import EasyTHPSensor

print("Example program for reading a Dexter Industries Temperature Humidity Pressure Sensor on an I2C port.")

my_thp = EasyTHPSensor()

while True:
# Read the temperature
temp = my_thp.safe_celsius()

# Read the relative humidity
hum = my_thp.safe_humidity()

# Read the pressure
press = my_thp.safe_pressure()

# Print the values
print("Temperature: {:5.3f} Humidity: {:5.3f} Pressure: {:5.3f}".format(temp, hum, press))

sleep(0.02)
58 changes: 29 additions & 29 deletions Python/di_sensors/BME280.py
Original file line number Diff line number Diff line change
Expand Up @@ -134,53 +134,53 @@ def __init__(self, bus = "RPI_1", t_mode = OSAMPLE_1, h_mode = OSAMPLE_1, p_mode
def _load_calibration(self):
# Read calibration data

self.dig_T1 = self.i2c_bus.read_reg_16u(REG_DIG_T1)
self.dig_T2 = self.i2c_bus.read_reg_16s(REG_DIG_T2)
self.dig_T3 = self.i2c_bus.read_reg_16s(REG_DIG_T3)

self.dig_P1 = self.i2c_bus.read_reg_16u(REG_DIG_P1)
self.dig_P2 = self.i2c_bus.read_reg_16s(REG_DIG_P2)
self.dig_P3 = self.i2c_bus.read_reg_16s(REG_DIG_P3)
self.dig_P4 = self.i2c_bus.read_reg_16s(REG_DIG_P4)
self.dig_P5 = self.i2c_bus.read_reg_16s(REG_DIG_P5)
self.dig_P6 = self.i2c_bus.read_reg_16s(REG_DIG_P6)
self.dig_P7 = self.i2c_bus.read_reg_16s(REG_DIG_P7)
self.dig_P8 = self.i2c_bus.read_reg_16s(REG_DIG_P8)
self.dig_P9 = self.i2c_bus.read_reg_16s(REG_DIG_P9)

self.dig_H1 = self.i2c_bus.read_reg_8u(REG_DIG_H1)
self.dig_H2 = self.i2c_bus.read_reg_16s(REG_DIG_H2)
self.dig_H3 = self.i2c_bus.read_reg_8u(REG_DIG_H3)
self.dig_H6 = self.i2c_bus.read_reg_8s(REG_DIG_H7)

h4 = self.i2c_bus.read_reg_8s(REG_DIG_H4)
self.dig_T1 = self.i2c_bus.read_16(REG_DIG_T1)
self.dig_T2 = self.i2c_bus.read_16(REG_DIG_T2, signed = True)
self.dig_T3 = self.i2c_bus.read_16(REG_DIG_T3, signed = True)

self.dig_P1 = self.i2c_bus.read_16(REG_DIG_P1)
self.dig_P2 = self.i2c_bus.read_16(REG_DIG_P2, signed = True)
self.dig_P3 = self.i2c_bus.read_16(REG_DIG_P3, signed = True)
self.dig_P4 = self.i2c_bus.read_16(REG_DIG_P4, signed = True)
self.dig_P5 = self.i2c_bus.read_16(REG_DIG_P5, signed = True)
self.dig_P6 = self.i2c_bus.read_16(REG_DIG_P6, signed = True)
self.dig_P7 = self.i2c_bus.read_16(REG_DIG_P7, signed = True)
self.dig_P8 = self.i2c_bus.read_16(REG_DIG_P8, signed = True)
self.dig_P9 = self.i2c_bus.read_16(REG_DIG_P9, signed = True)

self.dig_H1 = self.i2c_bus.read_8(REG_DIG_H1)
self.dig_H2 = self.i2c_bus.read_16(REG_DIG_H2, signed = True)
self.dig_H3 = self.i2c_bus.read_8(REG_DIG_H3)
self.dig_H6 = self.i2c_bus.read_8(REG_DIG_H7, signed = True)

h4 = self.i2c_bus.read_8(REG_DIG_H4, signed = True)
h4 = (h4 << 4)
self.dig_H4 = h4 | (self.i2c_bus.read_reg_8u(REG_DIG_H5) & 0x0F)
self.dig_H4 = h4 | (self.i2c_bus.read_8(REG_DIG_H5) & 0x0F)

h5 = self.i2c_bus.read_reg_8s(REG_DIG_H6)
h5 = self.i2c_bus.read_8(REG_DIG_H6, signed = True)
h5 = (h5 << 4)
self.dig_H5 = h5 | (
self.i2c_bus.read_reg_8u(REG_DIG_H5) >> 4 & 0x0F)
self.i2c_bus.read_8(REG_DIG_H5) >> 4 & 0x0F)

def _read_raw_temp(self):
# read raw temperature data once it's available
while (self.i2c_bus.read_reg_8u(REG_STATUS) & 0x08):
while (self.i2c_bus.read_8(REG_STATUS) & 0x08):
time.sleep(0.002)
data = self.i2c_bus.read_reg_list(REG_TEMP_DATA, 3)
data = self.i2c_bus.read_list(REG_TEMP_DATA, 3)
return ((data[0] << 16) | (data[1] << 8) | data[2]) >> 4

def _read_raw_pressure(self):
# read raw pressure data once it's available
while (self.i2c_bus.read_reg_8u(REG_STATUS) & 0x08):
while (self.i2c_bus.read_8(REG_STATUS) & 0x08):
time.sleep(0.002)
data = self.i2c_bus.read_reg_list(REG_PRESSURE_DATA, 3)
data = self.i2c_bus.read_list(REG_PRESSURE_DATA, 3)
return ((data[0] << 16) | (data[1] << 8) | data[2]) >> 4

def _read_raw_humidity(self):
# read raw humidity data once it's available
while (self.i2c_bus.read_reg_8u(REG_STATUS) & 0x08):
while (self.i2c_bus.read_8(REG_STATUS) & 0x08):
time.sleep(0.002)
data = self.i2c_bus.read_reg_list(REG_HUMIDITY_DATA, 2)
data = self.i2c_bus.read_list(REG_HUMIDITY_DATA, 2)
return (data[0] << 8) | data[1]

def read_temperature(self):
Expand Down
36 changes: 18 additions & 18 deletions Python/di_sensors/BNO055.py
Original file line number Diff line number Diff line change
Expand Up @@ -232,10 +232,10 @@ def __init__(self, bus = "RPI_1", address = ADDRESS_A, mode = OPERATION_MODE_NDO
self.i2c_bus.write_reg_8(REG_PAGE_ID, 0)

# check the chip ID
if ID != self.i2c_bus.read_reg_8u(REG_CHIP_ID):
if ID != self.i2c_bus.read_8(REG_CHIP_ID):
raise RuntimeError("BNO055 failed to respond")

if self.i2c_bus.read_reg_8u(REG_TEMP_SOURCE) != 0x01:
if self.i2c_bus.read_8(REG_TEMP_SOURCE) != 0x01:
# print("Doing init")

# reset the device using the reset command
Expand Down Expand Up @@ -288,12 +288,12 @@ def get_revision(self):
Returns a tuple with revision numbers for Software revision, Bootloader
version, Accelerometer ID, Magnetometer ID, and Gyro ID."""
# Read revision values.
accel = self.i2c_bus.read_reg_8u(REG_ACCEL_REV_ID)
mag = self.i2c_bus.read_reg_8u(REG_MAG_REV_ID)
gyro = self.i2c_bus.read_reg_8u(REG_GYRO_REV_ID)
bl = self.i2c_bus.read_reg_8u(REG_BL_REV_ID)
sw_lsb = self.i2c_bus.read_reg_8u(REG_SW_REV_ID_LSB)
sw_msb = self.i2c_bus.read_reg_8u(REG_SW_REV_ID_MSB)
accel = self.i2c_bus.read_8(REG_ACCEL_REV_ID)
mag = self.i2c_bus.read_8(REG_MAG_REV_ID)
gyro = self.i2c_bus.read_8(REG_GYRO_REV_ID)
bl = self.i2c_bus.read_8(REG_BL_REV_ID)
sw_lsb = self.i2c_bus.read_8(REG_SW_REV_ID_LSB)
sw_msb = self.i2c_bus.read_8(REG_SW_REV_ID_MSB)
sw = ((sw_msb << 8) | sw_lsb) & 0xFFFF
# Return the results as a tuple of all 5 values.
return (sw, bl, accel, mag, gyro)
Expand Down Expand Up @@ -353,20 +353,20 @@ def get_system_status(self, run_self_test = True):
# Switch to configuration mode if running self test.
self._config_mode()
# Perform a self test.
sys_trigger = self.i2c_bus.read_reg_8u(REG_SYS_TRIGGER)
sys_trigger = self.i2c_bus.read_8(REG_SYS_TRIGGER)
self.i2c_bus.write_reg_8(REG_SYS_TRIGGER, sys_trigger | 0x1)
# Wait for self test to finish.
time.sleep(1.0)
# Read test result.
self_test = self.i2c_bus.read_reg_8u(REG_SELFTEST_RESULT)
self_test = self.i2c_bus.read_8(REG_SELFTEST_RESULT)
# Go back to operation mode.
self._operation_mode()
else:
self_test = None

# read status and error values
status = self.i2c_bus.read_reg_8u(REG_SYS_STAT)
error = self.i2c_bus.read_reg_8u(REG_SYS_ERR)
status = self.i2c_bus.read_8(REG_SYS_STAT)
error = self.i2c_bus.read_8(REG_SYS_ERR)

# return the results as a tuple of all 3 values
return (status, self_test, error)
Expand Down Expand Up @@ -395,7 +395,7 @@ def get_calibration_status(self):
"""
# Return the calibration status register value.
cal_status = self.i2c_bus.read_reg_8u(REG_CALIB_STAT)
cal_status = self.i2c_bus.read_8(REG_CALIB_STAT)
sys = (cal_status >> 6) & 0x03
gyro = (cal_status >> 4) & 0x03
accel = (cal_status >> 2) & 0x03
Expand All @@ -413,7 +413,7 @@ def get_calibration(self):
# Switch to configuration mode, as mentioned in section 3.10.4 of datasheet.
self._config_mode()
# Read the 22 bytes of calibration data
cal_data = self.i2c_bus.read_reg_list(REG_ACCEL_OFFSET_X_LSB, 22)
cal_data = self.i2c_bus.read_list(REG_ACCEL_OFFSET_X_LSB, 22)
# Go back to normal operation mode.
self._operation_mode()
return cal_data
Expand Down Expand Up @@ -464,12 +464,12 @@ def get_axis_remap(self):
|____________|/
"""
# Get the axis remap register value.
map_config = self.i2c_bus.read_reg_8u(REG_AXIS_MAP_CONFIG)
map_config = self.i2c_bus.read_8(REG_AXIS_MAP_CONFIG)
z = (map_config >> 4) & 0x03
y = (map_config >> 2) & 0x03
x = map_config & 0x03
# Get the axis remap sign register value.
sign_config = self.i2c_bus.read_reg_8u(REG_AXIS_MAP_SIGN)
sign_config = self.i2c_bus.read_8(REG_AXIS_MAP_SIGN)
x_sign = (sign_config >> 2) & 0x01
y_sign = (sign_config >> 1) & 0x01
z_sign = sign_config & 0x01
Expand Down Expand Up @@ -510,7 +510,7 @@ def set_axis_remap(self, x, y, z, x_sign=AXIS_REMAP_POSITIVE,
def _read_vector(self, reg, count = 3):
# Read count number of 16-bit signed values starting from the provided
# register. Returns a tuple of the values that were read.
data = self.i2c_bus.read_reg_list(reg, count*2)
data = self.i2c_bus.read_list(reg, count*2)
result = [0]*count
for i in range(count):
result[i] = (((data[(i * 2) + 1] & 0xFF) << 8) | (data[(i * 2)] & 0xFF)) & 0xFFFF
Expand Down Expand Up @@ -573,4 +573,4 @@ def read_temp(self):
"""Read the temperature
Returns the current temperature in degrees celsius."""
return self.i2c_bus.read_reg_8s(REG_TEMP)
return self.i2c_bus.read_8(REG_TEMP, signed = True)
2 changes: 1 addition & 1 deletion Python/di_sensors/PCA9570.py
Original file line number Diff line number Diff line change
Expand Up @@ -36,4 +36,4 @@ def get_pins(self):
"""Get the output pin states
Returns the bit values for the 4 outputs"""
return (self.i2c_bus.read_8u() & 0x0F)
return (self.i2c_bus.read_8() & 0x0F)
Loading

0 comments on commit 8c72f81

Please sign in to comment.