|
| 1 | +from aiohttp import web |
| 2 | +import socketio |
| 3 | +import asyncio |
| 4 | +from gpiozero import CPUTemperature |
| 5 | +import serial |
| 6 | +import pygame |
| 7 | +import os |
| 8 | + |
| 9 | +sio = socketio.AsyncServer() |
| 10 | +app = web.Application() |
| 11 | +sio.attach(app) |
| 12 | +loop = asyncio.get_event_loop() |
| 13 | +pygame.display.init() |
| 14 | + |
| 15 | + |
| 16 | + |
| 17 | +ser = serial.Serial( |
| 18 | + port='/dev/ttyS0', #Replace ttyS0 with ttyAM0 for Pi1,Pi2,Pi0 |
| 19 | + baudrate = 115200, |
| 20 | + parity=serial.PARITY_NONE, |
| 21 | + stopbits=serial.STOPBITS_ONE, |
| 22 | + bytesize=serial.EIGHTBITS, |
| 23 | + timeout=0.01 |
| 24 | +) |
| 25 | + |
| 26 | +async def serLoop(): |
| 27 | + line = [] |
| 28 | + while True: |
| 29 | + await asyncio.sleep(0.2) |
| 30 | + for c in ser.read(): |
| 31 | + line.append(chr(int(c))) |
| 32 | + if chr(int(c)) == '\n': |
| 33 | + strSeg = ''.join(line).replace("\n", "") |
| 34 | + strSeg = strSeg.split(" ") |
| 35 | + if(len(strSeg) > 0): |
| 36 | + if(strSeg[0] == 'v'): |
| 37 | + await sio.emit('volt', float(strSeg[1])) |
| 38 | + line = [] |
| 39 | + break |
| 40 | + |
| 41 | +async def gameLoop(): |
| 42 | + while True: |
| 43 | + try: |
| 44 | + pygame.joystick.init() |
| 45 | + # Check if there is a joystick |
| 46 | + if(pygame.joystick.get_count()) < 1: |
| 47 | + pygame.joystick.quit() |
| 48 | + await asyncio.sleep(1) |
| 49 | + else: |
| 50 | + joystick = pygame.joystick.Joystick(0) |
| 51 | + break |
| 52 | + except pygame.error: |
| 53 | + pygame.joystick.quit() |
| 54 | + await asyncio.sleep(1) |
| 55 | + while True: |
| 56 | + try: |
| 57 | + await asyncio.sleep(0.01) |
| 58 | + joystick.init() |
| 59 | + |
| 60 | + if joystick.get_button(6): |
| 61 | + ser.write(('g 1\n').encode('utf-8')) |
| 62 | + if joystick.get_button(7): |
| 63 | + ser.write(('g -1\n').encode('utf-8')) |
| 64 | + if joystick.get_hat(0)[1] == 1: |
| 65 | + ser.write(('t 0 0 -0.3\n').encode('utf-8')) |
| 66 | + if joystick.get_hat(0)[1] == -1: |
| 67 | + ser.write(('t 0 0 0.3\n').encode('utf-8')) |
| 68 | + |
| 69 | + # Check for events |
| 70 | + for event in pygame.event.get(): |
| 71 | + if event.type == pygame.JOYBUTTONDOWN: |
| 72 | + if joystick.get_button(3): |
| 73 | + ser.write(('d\n').encode('utf-8')) |
| 74 | + elif joystick.get_button(4): |
| 75 | + ser.write(('u\n').encode('utf-8')) |
| 76 | + elif joystick.get_button(15): |
| 77 | + ser.write(('a\n').encode('utf-8')) |
| 78 | + elif joystick.get_button(11): |
| 79 | + ser.write(('b\n').encode('utf-8')) |
| 80 | + elif joystick.get_button(0): |
| 81 | + ser.write(('c\n').encode('utf-8')) |
| 82 | + elif joystick.get_button(1): |
| 83 | + ser.write(('o\n').encode('utf-8')) |
| 84 | + elif joystick.get_button(13): |
| 85 | + ser.write(('s\n').encode('utf-8')) |
| 86 | + if event.type == pygame.JOYAXISMOTION: |
| 87 | + axis0 = joystick.get_axis(0) |
| 88 | + axis1 = joystick.get_axis(1) |
| 89 | + axis2 = joystick.get_axis(2) |
| 90 | + axis3 = joystick.get_axis(3) |
| 91 | + axis4 = (joystick.get_axis(4) -joystick.get_axis(5))/2 |
| 92 | + |
| 93 | + msxString = "{:7.3f}".format(axis0*0.7) |
| 94 | + msyString = "{:7.3f}".format(-axis1*1.2) |
| 95 | + msrString = "{:7.3f}".format(axis4*0.8) |
| 96 | + yawString = "{:7.3f}".format(axis2/5) |
| 97 | + pitchString = "{:7.3f}".format(axis3/4) |
| 98 | + #print('m %s %s %s\n'%(msxString,msyString,msrString)) |
| 99 | + if joystick.get_button(6): |
| 100 | + ser.write(('t %s %s 0\n'%("{:7.3f}".format(-axis0*20), "{:7.3f}".format(-axis1*32))).encode('utf-8')) |
| 101 | + else: |
| 102 | + ser.write(('m %s %s %s\n'%(msxString, msyString, msrString)).encode('utf-8')) |
| 103 | + ser.write(('r 0 %s %s\n'%(pitchString, yawString)).encode('utf-8')) |
| 104 | + # Multiple events are generated for the same axis motion, so break after the first |
| 105 | + break |
| 106 | + except pygame.error: |
| 107 | + await asyncio.sleep(1) |
| 108 | + |
| 109 | +loop = asyncio.get_event_loop() |
| 110 | +loop.create_task(gameLoop()) |
| 111 | +serialLoop = asyncio.get_event_loop() |
| 112 | +serialLoop.create_task(serLoop()) |
| 113 | + |
| 114 | +def index(request): |
| 115 | + with open(os.path.dirname(__file__)+'/index.html') as f: |
| 116 | + return web.Response(text=f.read(), content_type='text/html') |
| 117 | + |
| 118 | +async def sendTemp(): |
| 119 | + while True: |
| 120 | + await asyncio.sleep(3) |
| 121 | + await sio.emit('temp', CPUTemperature().temperature) |
| 122 | + |
| 123 | +loop.create_task(sendTemp()) |
| 124 | + |
| 125 | +async def heartbeat(): |
| 126 | + while True: |
| 127 | + ser.write(('h\n').encode('utf-8')) |
| 128 | + await asyncio.sleep(1) |
| 129 | + |
| 130 | +loop.create_task(heartbeat()) |
| 131 | + |
| 132 | +@sio.on('connect') |
| 133 | +def chat_connection(sid, message): |
| 134 | + print('---- connected ----') |
| 135 | + |
| 136 | + |
| 137 | +@sio.on('disconnect') |
| 138 | +def chat_disconnect(sid): |
| 139 | + print('---- disconnected ----') |
| 140 | + |
| 141 | +@sio.on('mov') |
| 142 | +async def position(sid, msx, msy, msr): |
| 143 | + msxString = "{:7.3f}".format(float(msx)) |
| 144 | + msyString = "{:7.3f}".format(float(-msy)) |
| 145 | + msrString = "{:7.3f}".format(float(msr)) |
| 146 | + #print('m %s %s %s\n'%("000.000",msyString,msrString)) |
| 147 | + ser.write(('m %s %s %s\n'%(msxString,msyString,msrString)).encode('utf-8')) |
| 148 | + await asyncio.sleep(0.005) |
| 149 | + |
| 150 | +@sio.on('rot') |
| 151 | +async def position(sid, yaw, pitch, roll): |
| 152 | + yawString = "{:7.3f}".format(float(yaw/6)) |
| 153 | + pitchString = "{:7.3f}".format(float(pitch/6)) |
| 154 | + rollString = "{:7.3f}".format(float(roll/6)) |
| 155 | + ser.write(('r %s %s %s\n'%(rollString, pitchString, yawString)).encode('utf-8')) |
| 156 | + await asyncio.sleep(0.005) |
| 157 | + |
| 158 | +@sio.on('pos') |
| 159 | +async def position(sid, message): |
| 160 | + if message == 1: |
| 161 | + ser.write(('u\n').encode('utf-8')) |
| 162 | + if message == 0: |
| 163 | + ser.write(('d\n').encode('utf-8')) |
| 164 | + await asyncio.sleep(0.005) |
| 165 | + |
| 166 | +@sio.on('gait') |
| 167 | +async def position(sid, message): |
| 168 | + if message == 1: |
| 169 | + ser.write(('a\n').encode('utf-8')) |
| 170 | + elif message == 0: |
| 171 | + ser.write(('b\n').encode('utf-8')) |
| 172 | + await asyncio.sleep(0.005) |
| 173 | + |
| 174 | +@sio.on('claw') |
| 175 | +async def position(sid, message): |
| 176 | + if message == 1: |
| 177 | + ser.write(('c\n').encode('utf-8')) |
| 178 | + elif message == 0: |
| 179 | + ser.write(('o\n').encode('utf-8')) |
| 180 | + await asyncio.sleep(0.005) |
| 181 | + |
| 182 | +@sio.on('power') |
| 183 | +async def position(sid, message): |
| 184 | + if message == 1: |
| 185 | + print('power down') |
| 186 | + |
| 187 | +app.router.add_get('/', index) |
| 188 | + |
| 189 | +if __name__ == '__main__': |
| 190 | + web.run_app(app, host='0.0.0.0', port=3000) |
| 191 | + loop.run_forever() |
| 192 | + serialLoop.run_forever() |
| 193 | + |
0 commit comments