migrate to package

This commit is contained in:
Siwat Sirichai 2022-10-30 13:29:32 +07:00
parent 3d5a084b47
commit 50fc6dda3f
16 changed files with 52 additions and 7 deletions

0
kuukar/__init__.py Normal file
View file

View file

@ -0,0 +1,17 @@
from telemetrix_rpi_pico import telemetrix_rpi_pico
from kuukar_config import COLLISION_DETECTOR_PIN
from kuukar_lcd import lcd
from kuukar_leds import leds
class collision:
def __init__(self, aux: telemetrix_rpi_pico.TelemetrixRpiPico, lcd: lcd, leds: leds) -> None:
self.aux = aux
self.lcd = lcd
self.leds = leds
aux.set_pin_mode_digital_input(COLLISION_DETECTOR_PIN, self.collision_handle)
def collision_handle(self, data):
val = data[2]
if val == 1:
self.leds.__flasher(r=255, g=0, b=0, duration=250)
self.lcd.play_video("keke_hurt")

39
kuukar/kuukar_config.py Normal file
View file

@ -0,0 +1,39 @@
SERIAL_DRIVER_BOARD = "/dev/serial/by-id/..."
# HC Sonar Pins
SONAR_1_TRIG_PIN = 0
SONAR_1_ECHO_PIN = 1
SONAR_2_TRIG_PIN = 2
SONAR_2_ECHO_PIN = 3
SONAR_3_TRIG_PIN = 4
SONAR_3_ECHO_PIN = 5
# Motor Pins
MOTOR_FL_F = 6
MOTOR_FL_R = 7
MOTOR_FR_F = 8
MOTOR_FR_R = 9
MOTOR_RL_F = 10
MOTOR_RL_R = 11
MOTOR_RR_F = 12
MOTOR_RR_R = 13
# Full Speed 90 Degrees Turn Time
TURN_TIME_FS_90DEG_MS = 1500
SERIAL_AUX_BOARD = "/dev/serial/by-id/..."
COLLISION_DETECTOR_PIN = 2
LEDS_DATA_PIN = 3
LEDS_NUM = 15
HEADLIGHT_LEDS = [5, 10]
LEFT_SIGNAL_LEDS = [6, 3]
RIGHT_SIGNAL_LEDS = [7, 4]
REVERSE_LEDS = [1, 2]
LIGHT_ANALOG_PIN = 0
DHT22_PIN = 5
SERIAL_LCD = "/dev/serial/by-id/..."

17
kuukar/kuukar_cv.py Normal file
View file

@ -0,0 +1,17 @@
from kuukar_lcd import lcd
from kuukar_leds import leds
class cv:
def __init__(self, lcd: lcd, leds: leds) -> None:
self.lcd = lcd
self.leds = leds
def capture_image(self):
pass
def detect_face(self, image):
pass
def handle_face_detected(self):
pass

View file

@ -0,0 +1,37 @@
import threading
from time import sleep
from kuukar_lcd import lcd
from kuukar_leds import leds
from kuukar_sensors import sensors
class environment:
t_alerted = False
h_alerted = False
def __init__(self, lcd: lcd, leds: leds, sensors: sensors) -> None:
self.lcd = lcd
self.leds = leds
self.sensors = sensors
threading.Thread(target=self.__checker).start()
def __checker(self):
while True:
if self.sensors.get_temperature() > 38.0:
if not self.t_alerted:
lcd.play_video("keke_died")
self.t_alerted = True
else:
self.t_alerted = False
if self.sensors.get_humidity_pct() > 60.0:
if not self.h_alerted:
lcd.play_video("keke_cute_noise")
self.h_alerted = True
else:
self.h_alerted = False
if self.sensors.get_brightness_pct() < 50:
self.leds.set_headlights(True)
else:
self.leds.set_headlights(False)
sleep(1)

21
kuukar/kuukar_lcd.py Normal file
View file

@ -0,0 +1,21 @@
import kuukar_nextion
class lcd:
def __init__(self) -> None:
self.nextion = kuukar_nextion.nextion()
self.nextion.send_command("page home")
def play_video(self,filename: str) -> None:
self.nextion.send_command("page video_player")
self.nextion.send_command("video.path=\"sd0/"+filename+".video\"")
self.nextion.send_command("video.en=1")
def pause_video(self) -> None:
self.nextion.send_command("video.en=2")
def resume_video(self) -> None:
self.nextion.send_command("video.en=1")
def stop_video(self) -> None:
self.nextion.send_command("video.en=0")
self.nextion.send_command("page home")

80
kuukar/kuukar_leds.py Normal file
View file

@ -0,0 +1,80 @@
import threading
from time import perf_counter
from telemetrix_rpi_pico import telemetrix_rpi_pico
import time
from kuukar_config import LEDS_DATA_PIN, LEDS_NUM, HEADLIGHT_LEDS, LEFT_SIGNAL_LEDS, RIGHT_SIGNAL_LEDS, REVERSE_LEDS
class leds:
flashing = False
headlight = False
reverse_signal = False
left_signal = False
right_signal = False
ambient_light = [0, 0, 0]
start_time = perf_counter()
def __init__(self, aux_board: telemetrix_rpi_pico.TelemetrixRpiPico) -> None:
self.aux_board = aux_board
self.aux_board.set_pin_mode_neopixel(LEDS_DATA_PIN, LEDS_NUM)
def set_headlights(self, state: bool):
headlight = True
self.__update_leds()
def set_left_signal_led(self, state: bool):
self.left_signal = state
self.__update_leds()
def set_right_signal_led(self, state: bool):
self.right_signal = state
self.__update_leds()
def set_ambient_led(self, r: int, g: int, b: int):
self.ambient_light = [r, g, b]
self.__update_leds()
def set_reverse_led(self, state: bool):
self.reverse_signal = True
self.__update_leds()
def __update_leds(self):
self.aux_board.neopixel_fill(r=self.ambient_light[0], g=self.ambient_light[1], b=self.ambient_light[2])
if self.headlight:
for led in HEADLIGHT_LEDS:
self.aux_board.neo_pixel_set_value(led, self.headlight * 255, self.headlight * 255,
self.headlight * 255)
if self.left_signal:
for led in LEFT_SIGNAL_LEDS:
self.aux_board.neo_pixel_set_value(led, 255, 0, 0)
if self.right_signal:
for led in RIGHT_SIGNAL_LEDS:
self.aux_board.neo_pixel_set_value(led, 255, 0, 0)
if self.reverse_signal:
for led in REVERSE_LEDS:
self.aux_board.neo_pixel_set_value(led, 255, 0, 0)
self.aux_board.neopixel_show()
def flash(self, r: int, g: int, b: int, duration: int):
if not self.flashing:
self.flashing = True
self.start_time = perf_counter()
threading.Thread(target=self.__flasher, args=(r, g, b, duration))
@staticmethod
def __blink_func(t: float, dur: float):
if t > dur:
return 0
return (-1 / (dur / 2.0) ** 2) * (t - dur / 2.0) ** 2 + 1
def __get_time(self) -> float:
return perf_counter() - self.start_time
def __flasher(self, r: int, g: int, b: int, duration: int):
while True:
print(leds.__blink_func(self.__get_time(), duration))
time.sleep(0.05)
if self.__get_time > duration:
flashing = False
break

101
kuukar/kuukar_motion.py Normal file
View file

@ -0,0 +1,101 @@
from random import randint
from kuukar_config import MOTOR_FL_F, MOTOR_FL_R, MOTOR_FR_F, MOTOR_FR_R, MOTOR_RL_F, MOTOR_RL_R, MOTOR_RR_F, MOTOR_RR_R, TURN_TIME_FS_90DEG_MS
import time
from kuukar_leds import leds
from kuukar_sensors import sensors
from telemetrix_rpi_pico import telemetrix_rpi_pico
import threading
class motion:
roaming = False
def __init__(self, driver_board: telemetrix_rpi_pico.TelemetrixRpiPico, leds: leds, sensors: sensors) -> None:
self.driver = driver_board
self.leds = leds
self.sensors = sensors
self.roam_thread = threading.Thread(target=self.roam_loop)
self.roam_thread.start()
drive_pins = [MOTOR_FL_F, MOTOR_FL_R, MOTOR_FR_F,
MOTOR_FR_R, MOTOR_RL_F, MOTOR_RL_R, MOTOR_RR_F, MOTOR_RR_R]
for drive_pin in drive_pins:
self.driver.set_pin_mode_pwm_output(drive_pin)
def motor_write(self, forward_pin: int, reverse_pin: int, speed: int):
if speed < 0:
self.driver.pwm_write(forward_pin, 0)
self.driver.pwm_write(reverse_pin, -speed)
elif speed >= 0:
self.driver.pwm_write(forward_pin, speed)
self.driver.pwm_write(reverse_pin, 0)
def drive(self, speed: int):
self.motor_write(MOTOR_FL_F, MOTOR_FL_R, speed)
self.motor_write(MOTOR_FR_F, MOTOR_FR_R, speed)
self.motor_write(MOTOR_RL_F, MOTOR_RL_R, speed)
self.motor_write(MOTOR_RR_F, MOTOR_RR_R, speed)
def turn(self, speed: int, duration: float):
if speed > 0:
self.leds.set_right_signal_led(True)
elif speed < 0:
self.leds.set_left_signal_led(True)
self.motor_write(MOTOR_FL_F, MOTOR_FL_R, speed)
self.motor_write(MOTOR_FR_F, MOTOR_FR_R, -speed)
self.motor_write(MOTOR_RL_F, MOTOR_RL_R, speed)
self.motor_write(MOTOR_RR_F, MOTOR_RR_R, -speed)
time.sleep(duration)
self.stop()
if speed > 0:
self.leds.set_right_signal_led(False)
elif speed < 0:
self.leds.set_left_signal_led(False)
def stop(self):
self.leds.set_left_signal_led(False)
self.leds.set_right_signal_led(False)
self.leds.set_reverse_led(False)
self.drive(0)
def roam_start(self):
self.roaming = True
def roam_stop(self):
self.roaming = False
def __roam_looper(self):
while True:
if self.roaming:
self.__roam_handle()
def __roam_handle(self):
self.drive(50)
f_dist = self.sensors.sonar_get_distance(2)
if 0 < f_dist < 20: # Close to collision, turn the vehicle
l_dist = self.sensors.sonar_get_distance
r_dist = self.sensors.sonar_get_distance
if l_dist < 20: # Left side is blocked
if r_dist < 20: # Both side are blocked, do a full 180deg turn
self.turn(100, 2*TURN_TIME_FS_90DEG_MS)
self.drive(50)
time.sleep(3)
else:
# Right Side is Free, turn right
self.turn(100, TURN_TIME_FS_90DEG_MS)
self.drive(50)
time.sleep(3)
elif r_dist < 20: # Right side is blocked, left side is free, turn left
self.turn(-100, TURN_TIME_FS_90DEG_MS)
else: # Both Side are free, randomize a direction
right: bool = randint(0, 1)
if right:
self.turn(100, TURN_TIME_FS_90DEG_MS)
self.drive(50)
time.sleep(3)
else:
self.turn(-100, TURN_TIME_FS_90DEG_MS)
self.drive(50)
time.sleep(3)
time.sleep(0.5)

99
kuukar/kuukar_nextion.py Normal file
View file

@ -0,0 +1,99 @@
import binascii
from time import sleep
import serial
import threading
from kuukar_config import SERIAL_LCD
DATATYPE_NUMBER = '71'
DATATYPE_STRING = '70'
PRESSTYPE_PRESS = '01'
PRESSTYPE_RELEASE = '00'
EVENT_TOUCH = '65'
class nextion:
__commands_output_buffer__ = []
def __init__(self) -> None:
self.device = serial.Serial(SERIAL_LCD, baudrate=19200, timeout=5)
self.__send_stop_bit()
self.reset_device()
threading.Thread(target=self.__serial_reader).start()
threading.Thread(target=self.__serial_writer__).start()
def send_command(self, command: str):
command = bytes(command, 'ascii')
self.__commands_output_buffer__.append(command)
def __serial_writer__(self):
if len(self.__commands_output_buffer__) > 0:
self.device.write(self.__commands_output_buffer__.pop(0))
self.__send_stop_bit()
def reset_device(self):
self.send_command("rest")
def __get_stop_bit(self) -> bytearray:
stop_bit = bytearray()
stop_bit.append(0xFF)
stop_bit.append(0xFF)
stop_bit.append(0XFF)
return stop_bit
def __send_stop_bit(self):
self.device.write(self.__get_stop_bit())
def __serial_reader(self) -> None:
ser = self.device
while True:
if self.allow_serial_read:
buffer_length = ser.in_waiting
if buffer_length > 0:
self.handle_serial(self.read_serial())
def read_serial(self) -> list:
ser = self.device
data = ser.read_until(self.get_stop_bit())
data = data[0:len(data)-3]
data: list = data.hex('/').split('/')
return data
def handle_serial(self, data: list):
message_type = data.pop(0)
if message_type == EVENT_TOUCH:
self.handle_touch_event(data)
def handle_touch_event(self, data: list):
page = int(data.pop(0), 16)
component_id = int(data.pop(0), 16)
press_type = data.pop(0)
print("Got a touch event at page "+str(page)+" in component "+str(component_id)
+ " with type "+str(press_type))
def get_attribute(self, attribute: str):
self.allow_serial_read = False
self.send_command("get "+str(attribute))
sleep(0.1)
data = self.read_serial()
self.allow_serial_read = True
data_type = data.pop(0)
if data_type == DATATYPE_STRING:
data = nextion.hex_string_list_to_bytes(data)
return data.decode('ascii')
elif data_type == DATATYPE_NUMBER:
return nextion.little_endian_to_int(data)
@staticmethod
def hex_string_list_to_bytes(hexstring_list: list) -> bytes:
hexstring = ''.join(hexstring_list)
return binascii.unhexlify(hexstring)
@staticmethod
def little_endian_to_int(data: list) -> int:
data.reverse()
hexstring = ''.join(data)
value = int(hexstring, 16)
return value

54
kuukar/kuukar_sensors.py Normal file
View file

@ -0,0 +1,54 @@
from telemetrix_rpi_pico import telemetrix_rpi_pico
from kuukar_config import DHT22_PIN, SONAR_1_ECHO_PIN, SONAR_1_TRIG_PIN,\
SONAR_2_ECHO_PIN, SONAR_2_TRIG_PIN, SONAR_3_ECHO_PIN, SONAR_3_TRIG_PIN,\
LIGHT_ANALOG_PIN
class sensors:
__sonar_trig_pins = [SONAR_1_TRIG_PIN,
SONAR_2_TRIG_PIN, SONAR_3_TRIG_PIN]
__sonar_distances = [0, 0, 0]
__temperature = 0
__humidity = 0
__brightness = 0
def __init__(self, aux_board: telemetrix_rpi_pico.TelemetrixRpiPico, driver_board: telemetrix_rpi_pico.TelemetrixRpiPico) -> None:
self.aux = aux_board
self.driver = driver_board
self.driver.set_pin_mode_sonar(
SONAR_1_TRIG_PIN, SONAR_1_ECHO_PIN, self.__sonar_callback)
self.driver.set_pin_mode_sonar(
SONAR_2_TRIG_PIN, SONAR_2_ECHO_PIN, self.__sonar_callback)
self.driver.set_pin_mode_sonar(
SONAR_3_TRIG_PIN, SONAR_3_ECHO_PIN, self.__sonar_callback)
self.driver.set_pin_mode_dht(DHT22_PIN, self.__dht22_callback)
self.aux.set_pin_mode_analog_input(LIGHT_ANALOG_PIN, 0, self.__light_sensor_callback())
def sonar_get_distance(self, id: int) -> float:
return self.__sonar_distances[id]
def __sonar_callback(self, data):
pin = data[1]
distance = data[2]
sonar_id = self.__sonar_trig_pins.index(pin)
self.__sonar_distances[sonar_id] = distance
def get_brightness_pct(self) -> float:
return self.__brightness
def get_temperature(self) -> float:
return self.__temperature
def get_humidity_pct(self) -> float:
return self.__humidity
def __light_sensor_callback(self, data):
self.__brightness = data[2]
def __dht22_callback(self, data):
humidity = data[3]
temperature = data[4]
self.__humidity = humidity
self.__temperature = temperature

11
kuukar/kuukar_voice.py Normal file
View file

@ -0,0 +1,11 @@
from kuukar_lcd import lcd
from kuukar_leds import leds
from kuukar_noise import noise
class voice:
def __init__(self, lcd: lcd, leds: leds) -> None:
self.lcd = lcd
self.leds = leds
def handle_voice_prompt(self, command):
pass