diff --git a/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/Example.ice b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/Example.ice new file mode 100644 index 00000000..a9a818a4 --- /dev/null +++ b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/Example.ice @@ -0,0 +1,1676 @@ +{ + "version": "1.2", + "package": { + "name": "ov7670_rgb_yuv", + "version": "1.1", + "description": "Configures ov7670 in either RGB444 or YUV and shows it", + "author": "Felipe Machado", + "image": "" + }, + "design": { + "board": "alhambra-ii", + "graph": { + "blocks": [ + { + "id": "5762721f-d258-4a65-8e56-b9e74c98972a", + "type": "basic.output", + "data": { + "name": "ss", + "pins": [ + { + "index": "0", + "name": "D4", + "value": "8" + } + ], + "virtual": false + }, + "position": { + "x": 568, + "y": -440 + } + }, + { + "id": "629f8b48-a6c0-4bd0-b04e-9bc99d550f5f", + "type": "basic.input", + "data": { + "name": "rst", + "pins": [ + { + "index": "0", + "name": "SW1", + "value": "34" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -176, + "y": -424 + } + }, + { + "id": "408c4263-1fd9-477e-866e-b522753745e4", + "type": "basic.output", + "data": { + "name": "sclk", + "pins": [ + { + "index": "0", + "name": "D0", + "value": "2" + } + ], + "virtual": false + }, + "position": { + "x": 1120, + "y": -288 + } + }, + { + "id": "39dbf40a-f91e-47a8-82ff-4f76416acabf", + "type": "basic.output", + "data": { + "name": "mosi_o", + "pins": [ + { + "index": "0", + "name": "D2", + "value": "4" + } + ], + "virtual": false + }, + "position": { + "x": 1112, + "y": -200 + } + }, + { + "id": "5d4099f3-f1ad-4f9f-8076-9e27369c9b9e", + "type": "basic.output", + "data": { + "name": "rpi_running", + "pins": [ + { + "index": "0", + "name": "D3", + "value": "3" + } + ], + "virtual": false + }, + "position": { + "x": 1112, + "y": -112 + } + }, + { + "id": "7a55fc31-5d15-4bca-8b14-93101f389387", + "type": "basic.input", + "data": { + "name": "miso", + "pins": [ + { + "index": "0", + "name": "D1", + "value": "1" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": 808, + "y": 72 + } + }, + { + "id": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "type": "1e3e2fe589ecba428455b3f167a8e84edb4c218b", + "position": { + "x": 352, + "y": -328 + }, + "size": { + "width": 96, + "height": 288 + } + }, + { + "id": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "type": "2efe39da646c359984049ea063338769e484bb63", + "position": { + "x": 912, + "y": -360 + }, + "size": { + "width": 96, + "height": 224 + } + }, + { + "id": "fed6a17d-60da-421c-bf3b-e490c6ac5d71", + "type": "basic.code", + "data": { + "code": "assign vel = 8'd40;", + "params": [], + "ports": { + "in": [], + "out": [ + { + "name": "vel", + "range": "[7:0]", + "size": 8 + } + ] + } + }, + "position": { + "x": -192, + "y": -296 + }, + "size": { + "width": 232, + "height": 64 + } + }, + { + "id": "6d96d919-f5fc-49f3-9aa1-4ace6ae960ee", + "type": "basic.code", + "data": { + "code": "assign led = 24'hff0000;", + "params": [], + "ports": { + "in": [], + "out": [ + { + "name": "led", + "range": "[23:0]", + "size": 24 + } + ] + } + }, + "position": { + "x": -200, + "y": -176 + }, + "size": { + "width": 232, + "height": 64 + } + } + ], + "wires": [ + { + "source": { + "block": "629f8b48-a6c0-4bd0-b04e-9bc99d550f5f", + "port": "out" + }, + "target": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "fff8810d-4cef-42d3-8896-8c9e4a496379" + }, + "vertices": [ + { + "x": 0, + "y": -344 + } + ] + }, + { + "source": { + "block": "629f8b48-a6c0-4bd0-b04e-9bc99d550f5f", + "port": "out" + }, + "target": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "cfbf8498-f0bc-4fb0-bc44-1a03a9e83e9c" + }, + "vertices": [ + { + "x": 656, + "y": -312 + } + ] + }, + { + "source": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "e86e026a-227d-4bf8-8c70-53ea31e04a3c" + }, + "target": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "f19e3f2e-32c6-4629-942e-f88704750d9d" + }, + "vertices": [ + { + "x": 632, + "y": -192 + } + ] + }, + { + "source": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "d34cf187-214e-4ae8-9603-3c41146647e3" + }, + "target": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "fd93ee0e-cc6f-4386-8d45-28d9ac257767" + }, + "vertices": [ + { + "x": 672, + "y": -248 + } + ] + }, + { + "source": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "bbd54035-423d-4fa2-82ca-59b83d57b3e9" + }, + "target": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "7c071aa2-1f78-462c-bbf1-b07283922ed1" + }, + "vertices": [ + { + "x": 664, + "y": -112 + } + ], + "size": 8 + }, + { + "source": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "fdc0b9ae-45ae-4285-86c8-6f8a66d97fb6" + }, + "target": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "a9a0f2c3-60e8-49c7-90c8-ee81b695e8a4" + }, + "vertices": [ + { + "x": 480, + "y": -496 + }, + { + "x": 288, + "y": -464 + } + ] + }, + { + "source": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "50e235e2-3385-4dc2-869c-a29a300b39be" + }, + "target": { + "block": "408c4263-1fd9-477e-866e-b522753745e4", + "port": "in" + } + }, + { + "source": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "3518615b-f740-4450-b702-e0eddcdcb7e4" + }, + "target": { + "block": "39dbf40a-f91e-47a8-82ff-4f76416acabf", + "port": "in" + } + }, + { + "source": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "3f8d97c2-b88b-4c8d-b717-480bf7b36b52" + }, + "target": { + "block": "5d4099f3-f1ad-4f9f-8076-9e27369c9b9e", + "port": "in" + } + }, + { + "source": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "50262b52-dd70-4386-94f6-b41d4259401d" + }, + "target": { + "block": "5762721f-d258-4a65-8e56-b9e74c98972a", + "port": "in" + } + }, + { + "source": { + "block": "7a55fc31-5d15-4bca-8b14-93101f389387", + "port": "out" + }, + "target": { + "block": "2e4462be-a255-413e-bfcf-be22fb521a8d", + "port": "6fd30186-e930-4605-8b97-b02c1302684e" + } + }, + { + "source": { + "block": "6d96d919-f5fc-49f3-9aa1-4ace6ae960ee", + "port": "led" + }, + "target": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "e20802df-0fbb-48e6-b5d4-89a3ab66a171" + }, + "size": 24 + }, + { + "source": { + "block": "fed6a17d-60da-421c-bf3b-e490c6ac5d71", + "port": "vel" + }, + "target": { + "block": "2dc732a5-b189-4835-bd8b-81594ce2f640", + "port": "bbc89353-68a5-4b76-8fbb-c196bdaf2dde" + }, + "size": 8 + } + ] + } + }, + "dependencies": { + "1e3e2fe589ecba428455b3f167a8e84edb4c218b": { + "package": { + "name": "GPG Control ", + "version": "", + "description": "", + "author": "rnicklas", + "image": "" + }, + "design": { + "graph": { + "blocks": [ + { + "id": "fff8810d-4cef-42d3-8896-8c9e4a496379", + "type": "basic.input", + "data": { + "name": "rst", + "clock": false + }, + "position": { + "x": -120, + "y": 144 + } + }, + { + "id": "50262b52-dd70-4386-94f6-b41d4259401d", + "type": "basic.output", + "data": { + "name": "spi_ss_n", + "virtual": false + }, + "position": { + "x": 832, + "y": 176 + } + }, + { + "id": "5db2bf01-b245-4887-b6bd-5c20bcc01c8b", + "type": "basic.input", + "data": { + "name": "clk", + "clock": true + }, + "position": { + "x": -120, + "y": 200 + } + }, + { + "id": "a9a0f2c3-60e8-49c7-90c8-ee81b695e8a4", + "type": "basic.input", + "data": { + "name": "busy_spi", + "clock": false + }, + "position": { + "x": -120, + "y": 248 + } + }, + { + "id": "d34cf187-214e-4ae8-9603-3c41146647e3", + "type": "basic.output", + "data": { + "name": "spi_send", + "virtual": false + }, + "position": { + "x": 824, + "y": 296 + } + }, + { + "id": "bbc89353-68a5-4b76-8fbb-c196bdaf2dde", + "type": "basic.input", + "data": { + "name": "motor_pwm_left_i", + "range": "[7:0]", + "pins": [ + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -120, + "y": 304 + } + }, + { + "id": "3c1f8a9d-1ff2-4dd1-8c1f-ba07ef274c80", + "type": "basic.input", + "data": { + "name": "motor_pwm_rght_i", + "range": "[7:0]", + "pins": [ + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -128, + "y": 360 + } + }, + { + "id": "e86e026a-227d-4bf8-8c70-53ea31e04a3c", + "type": "basic.output", + "data": { + "name": "ena_2clk" + }, + "position": { + "x": 824, + "y": 416 + } + }, + { + "id": "0395c4a7-859a-4bee-94a6-9a2642c9606e", + "type": "basic.input", + "data": { + "name": "led_eye_left_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -136, + "y": 416 + } + }, + { + "id": "e6c85cad-f473-4ceb-8de7-9a58743709bc", + "type": "basic.input", + "data": { + "name": "led_eye_rght_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -136, + "y": 464 + } + }, + { + "id": "065ed119-dca7-4790-b4a1-f6ffe79050ca", + "type": "basic.input", + "data": { + "name": "led_blink_left_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -136, + "y": 512 + } + }, + { + "id": "bbd54035-423d-4fa2-82ca-59b83d57b3e9", + "type": "basic.output", + "data": { + "name": "data_spi", + "range": "[7:0]", + "size": 8 + }, + "position": { + "x": 832, + "y": 536 + } + }, + { + "id": "e20802df-0fbb-48e6-b5d4-89a3ab66a171", + "type": "basic.input", + "data": { + "name": "led_blink_rght_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": false, + "clock": false + }, + "position": { + "x": -136, + "y": 560 + } + }, + { + "id": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "type": "basic.code", + "data": { + "code": "// @include spi_ledctrl.v\r\n\r\n spi_ledctrl i_spi_ledctrl\r\n (\r\n .rst (rst),\r\n .clk (clk),\r\n .busy_spi (busy_spi),\r\n .motor_pwm_left_i (motor_pwm_left_i),\r\n .motor_pwm_rght_i (motor_pwm_rght_i),\r\n .led_eye_left_rgb_i (led_eye_left_rgb_i),\r\n .led_eye_rght_rgb_i (led_eye_rght_rgb_i),\r\n .led_blink_left_rgb_i (led_blink_left_rgb_i),\r\n .led_blink_rght_rgb_i (led_blink_rght_rgb_i),\r\n .spi_ss_n (spi_ss_n), // spi slave select\r\n .spi_send (spi_send),\r\n .ena_2clk (ena_2clk),\r\n .data_spi (data_spi)\r\n );\r\n", + "params": [], + "ports": { + "in": [ + { + "name": "rst" + }, + { + "name": "clk" + }, + { + "name": "busy_spi" + }, + { + "name": "motor_pwm_left_i", + "range": "[7:0]", + "size": 8 + }, + { + "name": "motor_pwm_rght_i", + "range": "[7:0]", + "size": 8 + }, + { + "name": "led_eye_left_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_eye_rght_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_blink_left_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_blink_rght_rgb_i", + "range": "[23:0]", + "size": 24 + } + ], + "out": [ + { + "name": "spi_ss_n" + }, + { + "name": "spi_send" + }, + { + "name": "ena_2clk" + }, + { + "name": "data_spi", + "range": "[7:0]", + "size": 8 + } + ] + } + }, + "position": { + "x": 192, + "y": 152 + }, + "size": { + "width": 552, + "height": 472 + } + } + ], + "wires": [ + { + "source": { + "block": "5db2bf01-b245-4887-b6bd-5c20bcc01c8b", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "clk" + } + }, + { + "source": { + "block": "fff8810d-4cef-42d3-8896-8c9e4a496379", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "rst" + } + }, + { + "source": { + "block": "a9a0f2c3-60e8-49c7-90c8-ee81b695e8a4", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "busy_spi" + } + }, + { + "source": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "ena_2clk" + }, + "target": { + "block": "e86e026a-227d-4bf8-8c70-53ea31e04a3c", + "port": "in" + } + }, + { + "source": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "data_spi" + }, + "target": { + "block": "bbd54035-423d-4fa2-82ca-59b83d57b3e9", + "port": "in" + }, + "size": 8 + }, + { + "source": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "spi_send" + }, + "target": { + "block": "d34cf187-214e-4ae8-9603-3c41146647e3", + "port": "in" + } + }, + { + "source": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "spi_ss_n" + }, + "target": { + "block": "50262b52-dd70-4386-94f6-b41d4259401d", + "port": "in" + } + }, + { + "source": { + "block": "bbc89353-68a5-4b76-8fbb-c196bdaf2dde", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "motor_pwm_left_i" + }, + "size": 8 + }, + { + "source": { + "block": "3c1f8a9d-1ff2-4dd1-8c1f-ba07ef274c80", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "motor_pwm_rght_i" + }, + "size": 8 + }, + { + "source": { + "block": "0395c4a7-859a-4bee-94a6-9a2642c9606e", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "led_eye_left_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "e6c85cad-f473-4ceb-8de7-9a58743709bc", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "led_eye_rght_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "065ed119-dca7-4790-b4a1-f6ffe79050ca", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "led_blink_left_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "e20802df-0fbb-48e6-b5d4-89a3ab66a171", + "port": "out" + }, + "target": { + "block": "b4e7bdea-88b7-4a43-a26d-f3cde8c7a4e2", + "port": "led_blink_rght_rgb_i" + }, + "size": 24 + } + ] + } + } + }, + "2efe39da646c359984049ea063338769e484bb63": { + "package": { + "name": "", + "version": "", + "description": "", + "author": "", + "image": "" + }, + "design": { + "graph": { + "blocks": [ + { + "id": "e7cb9381-4164-4c25-ba00-72c37df2df31", + "type": "basic.input", + "data": { + "name": "clk", + "clock": true + }, + "position": { + "x": -176, + "y": 136 + } + }, + { + "id": "fdc0b9ae-45ae-4285-86c8-6f8a66d97fb6", + "type": "basic.output", + "data": { + "name": "busy_spi" + }, + "position": { + "x": 904, + "y": 144 + } + }, + { + "id": "cfbf8498-f0bc-4fb0-bc44-1a03a9e83e9c", + "type": "basic.input", + "data": { + "name": "rst", + "clock": false + }, + "position": { + "x": -200, + "y": 184 + } + }, + { + "id": "f19e3f2e-32c6-4629-942e-f88704750d9d", + "type": "basic.input", + "data": { + "name": "ena_2clk", + "clock": false + }, + "position": { + "x": -200, + "y": 240 + } + }, + { + "id": "fd93ee0e-cc6f-4386-8d45-28d9ac257767", + "type": "basic.input", + "data": { + "name": "start", + "clock": false + }, + "position": { + "x": -216, + "y": 304 + } + }, + { + "id": "50e235e2-3385-4dc2-869c-a29a300b39be", + "type": "basic.output", + "data": { + "name": "sclk_o" + }, + "position": { + "x": 920, + "y": 328 + } + }, + { + "id": "7c071aa2-1f78-462c-bbf1-b07283922ed1", + "type": "basic.input", + "data": { + "name": "data_spi", + "range": "[7:0]", + "clock": false, + "size": 8 + }, + "position": { + "x": -208, + "y": 384 + } + }, + { + "id": "af6f65e2-a2a6-49c8-a6d7-f27154f3cc76", + "type": "basic.input", + "data": { + "name": "ack", + "clock": false + }, + "position": { + "x": -56, + "y": 456 + } + }, + { + "id": "3518615b-f740-4450-b702-e0eddcdcb7e4", + "type": "basic.output", + "data": { + "name": "mosi_o" + }, + "position": { + "x": 912, + "y": 480 + } + }, + { + "id": "3f8d97c2-b88b-4c8d-b717-480bf7b36b52", + "type": "basic.output", + "data": { + "name": "rpi_run" + }, + "position": { + "x": 856, + "y": 552 + } + }, + { + "id": "6fd30186-e930-4605-8b97-b02c1302684e", + "type": "basic.input", + "data": { + "name": "miso_i", + "clock": false + }, + "position": { + "x": -216, + "y": 576 + } + }, + { + "id": "686efab2-218f-40e8-a203-454f35652261", + "type": "basic.code", + "data": { + "code": "// @include spi_master.v\r\n \r\n SPI_Master i_spi_master\r\n (\r\n // System\r\n .clk_i (clk),\r\n .rst_i (rst),\r\n .ena_i (ena_2clk), // 2*SCK\r\n // Interface\r\n .start_i (start),\r\n .ack_i (ack), // IRQ Ack\r\n .tx_i (data_spi),\r\n .busy_o (busy_spi), \r\n\r\n // SPI\r\n .sclk_o (sclk_o), \r\n .miso_i (miso_i),\r\n //.mosi_en_o (ssb), \r\n .mosi_o (mosi_o),\r\n .rpi_running (rpi_running)\r\n );\r\n", + "params": [], + "ports": { + "in": [ + { + "name": "clk" + }, + { + "name": "rst" + }, + { + "name": "ena_2clk" + }, + { + "name": "start" + }, + { + "name": "data_spi", + "range": "[7:0]", + "size": 8 + }, + { + "name": "ack" + }, + { + "name": "miso_i" + } + ], + "out": [ + { + "name": "busy_spi" + }, + { + "name": "sclk_o" + }, + { + "name": "mosi_o" + }, + { + "name": "rpi_running" + } + ] + } + }, + "position": { + "x": 208, + "y": 144 + }, + "size": { + "width": 544, + "height": 448 + } + } + ], + "wires": [ + { + "source": { + "block": "e7cb9381-4164-4c25-ba00-72c37df2df31", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "clk" + } + }, + { + "source": { + "block": "cfbf8498-f0bc-4fb0-bc44-1a03a9e83e9c", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "rst" + } + }, + { + "source": { + "block": "f19e3f2e-32c6-4629-942e-f88704750d9d", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "ena_2clk" + } + }, + { + "source": { + "block": "fd93ee0e-cc6f-4386-8d45-28d9ac257767", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "start" + } + }, + { + "source": { + "block": "7c071aa2-1f78-462c-bbf1-b07283922ed1", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "data_spi" + }, + "vertices": [ + { + "x": -56, + "y": 368 + } + ], + "size": 8 + }, + { + "source": { + "block": "af6f65e2-a2a6-49c8-a6d7-f27154f3cc76", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "ack" + } + }, + { + "source": { + "block": "6fd30186-e930-4605-8b97-b02c1302684e", + "port": "out" + }, + "target": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "miso_i" + } + }, + { + "source": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "busy_spi" + }, + "target": { + "block": "fdc0b9ae-45ae-4285-86c8-6f8a66d97fb6", + "port": "in" + } + }, + { + "source": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "sclk_o" + }, + "target": { + "block": "50e235e2-3385-4dc2-869c-a29a300b39be", + "port": "in" + } + }, + { + "source": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "mosi_o" + }, + "target": { + "block": "3518615b-f740-4450-b702-e0eddcdcb7e4", + "port": "in" + } + }, + { + "source": { + "block": "686efab2-218f-40e8-a203-454f35652261", + "port": "rpi_running" + }, + "target": { + "block": "3f8d97c2-b88b-4c8d-b717-480bf7b36b52", + "port": "in" + } + } + ] + } + } + } + } +} \ No newline at end of file diff --git a/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.ice b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.ice new file mode 100644 index 00000000..5d899c40 --- /dev/null +++ b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.ice @@ -0,0 +1,1060 @@ +{ + "version": "1.2", + "package": { + "name": "GoPiGo Controller ", + "version": "1.0", + "description": "", + "author": "JdeRobot", + "image": "" + }, + "design": { + "board": "alhambra-ii", + "graph": { + "blocks": [ + { + "id": "7be2ddb1-d6a1-4bd7-ae61-39bfb790c83a", + "type": "basic.input", + "data": { + "name": "rst", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": 96, + "y": 208 + } + }, + { + "id": "69dc2722-2a9d-4126-b109-7e31cfea16b6", + "type": "basic.output", + "data": { + "name": "spi_ss_n", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true + }, + "position": { + "x": 968, + "y": 224 + } + }, + { + "id": "a1e8c8a0-be11-4a4d-a19e-f8ee03fa17ae", + "type": "basic.input", + "data": { + "name": "clk", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": true + }, + "position": { + "x": -40, + "y": 256 + } + }, + { + "id": "27b9b159-fff3-4aa8-a549-d95bf7cffa35", + "type": "basic.input", + "data": { + "name": "busy_spi", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": 88, + "y": 296 + } + }, + { + "id": "252056ef-9e93-4572-9542-6c05ab5014f3", + "type": "basic.output", + "data": { + "name": "spi_send", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true + }, + "position": { + "x": 984, + "y": 344 + } + }, + { + "id": "30efe8a5-78b5-4d54-9240-38fe50b23cf7", + "type": "basic.input", + "data": { + "name": "motor_pwm_left_i", + "range": "[7:0]", + "pins": [ + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -96, + "y": 352 + } + }, + { + "id": "d9089370-ca82-4916-a658-332acf5559d7", + "type": "basic.input", + "data": { + "name": "motor_pwm_rght_i", + "range": "[7:0]", + "pins": [ + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -96, + "y": 400 + } + }, + { + "id": "76d276fd-4d90-4f03-8e17-82b1cebc95b0", + "type": "basic.input", + "data": { + "name": "led_eye_left_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -104, + "y": 456 + } + }, + { + "id": "a4ff0e57-8710-43bd-84f6-c41eded90435", + "type": "basic.output", + "data": { + "name": "ena_2clk", + "pins": [ + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true + }, + "position": { + "x": 960, + "y": 464 + } + }, + { + "id": "653def34-7abb-4924-8f15-8e326f02964e", + "type": "basic.input", + "data": { + "name": "led_eye_rght_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -104, + "y": 504 + } + }, + { + "id": "136cc2a3-009b-455d-aecb-b26cb259e486", + "type": "basic.input", + "data": { + "name": "led_eye_left_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -104, + "y": 552 + } + }, + { + "id": "4e2de48f-16d4-4669-be41-bcdd717f6a58", + "type": "basic.output", + "data": { + "name": "data_spi", + "range": "[7:0]", + "pins": [ + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true + }, + "position": { + "x": 968, + "y": 592 + } + }, + { + "id": "5191ecd2-99f0-4b5b-9a5f-d10e8f8f7509", + "type": "basic.input", + "data": { + "name": "led_blink_rght_rgb_i", + "range": "[23:0]", + "pins": [ + { + "index": "23", + "name": "", + "value": "" + }, + { + "index": "22", + "name": "", + "value": "" + }, + { + "index": "21", + "name": "", + "value": "" + }, + { + "index": "20", + "name": "", + "value": "" + }, + { + "index": "19", + "name": "", + "value": "" + }, + { + "index": "18", + "name": "", + "value": "" + }, + { + "index": "17", + "name": "", + "value": "" + }, + { + "index": "16", + "name": "", + "value": "" + }, + { + "index": "15", + "name": "", + "value": "" + }, + { + "index": "14", + "name": "", + "value": "" + }, + { + "index": "13", + "name": "", + "value": "" + }, + { + "index": "12", + "name": "", + "value": "" + }, + { + "index": "11", + "name": "", + "value": "" + }, + { + "index": "10", + "name": "", + "value": "" + }, + { + "index": "9", + "name": "", + "value": "" + }, + { + "index": "8", + "name": "", + "value": "" + }, + { + "index": "7", + "name": "", + "value": "" + }, + { + "index": "6", + "name": "", + "value": "" + }, + { + "index": "5", + "name": "", + "value": "" + }, + { + "index": "4", + "name": "", + "value": "" + }, + { + "index": "3", + "name": "", + "value": "" + }, + { + "index": "2", + "name": "", + "value": "" + }, + { + "index": "1", + "name": "", + "value": "" + }, + { + "index": "0", + "name": "", + "value": "" + } + ], + "virtual": true, + "clock": false + }, + "position": { + "x": -104, + "y": 616 + } + }, + { + "id": "734d9762-f219-4091-8639-8f686819de29", + "type": "basic.code", + "data": { + "code": "// @include spi_ledctrl.v\r\n\r\n spi_ledctrl i_spi_ledctrl\r\n (\r\n .rst (rst),\r\n .clk (clk),\r\n .busy_spi (busy_spi),\r\n .motor_pwm_left_i (motor_pwm_left_i),\r\n .motor_pwm_rght_i (motor_pwm_rght_i),\r\n .led_eye_left_rgb_i (led_eye_left_rgb_i),\r\n .led_eye_rght_rgb_i (led_eye_rght_rgb_i),\r\n .led_blink_left_rgb_i (led_blink_left_rgb_i),\r\n .led_blink_rght_rgb_i (led_blink_rght_rgb_i),\r\n .spi_ss_n (spi_ss_n), // spi slave select\r\n .spi_send (spi_send),\r\n .ena_2clk (ena_2clk),\r\n .data_spi (data_spi)\r\n );\r\n", + "params": [], + "ports": { + "in": [ + { + "name": "rst" + }, + { + "name": "clk" + }, + { + "name": "busy_spi" + }, + { + "name": "motor_pwm_left_i", + "range": "[7:0]", + "size": 8 + }, + { + "name": "motor_pwm_rght_i", + "range": "[7:0]", + "size": 8 + }, + { + "name": "led_eye_left_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_eye_rght_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_blink_left_rgb_i", + "range": "[23:0]", + "size": 24 + }, + { + "name": "led_blink_rght_rgb_i", + "range": "[23:0]", + "size": 24 + } + ], + "out": [ + { + "name": "spi_ss_n" + }, + { + "name": "spi_send" + }, + { + "name": "ena_2clk" + }, + { + "name": "data_spi", + "range": "[7:0]", + "size": 8 + } + ] + } + }, + "position": { + "x": 280, + "y": 208 + }, + "size": { + "width": 552, + "height": 472 + } + } + ], + "wires": [ + { + "source": { + "block": "7be2ddb1-d6a1-4bd7-ae61-39bfb790c83a", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "rst" + } + }, + { + "source": { + "block": "27b9b159-fff3-4aa8-a549-d95bf7cffa35", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "busy_spi" + } + }, + { + "source": { + "block": "30efe8a5-78b5-4d54-9240-38fe50b23cf7", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "motor_pwm_left_i" + }, + "size": 8 + }, + { + "source": { + "block": "d9089370-ca82-4916-a658-332acf5559d7", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "motor_pwm_rght_i" + }, + "size": 8 + }, + { + "source": { + "block": "76d276fd-4d90-4f03-8e17-82b1cebc95b0", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "led_eye_left_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "653def34-7abb-4924-8f15-8e326f02964e", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "led_eye_rght_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "5191ecd2-99f0-4b5b-9a5f-d10e8f8f7509", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "led_blink_rght_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "136cc2a3-009b-455d-aecb-b26cb259e486", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "led_blink_left_rgb_i" + }, + "size": 24 + }, + { + "source": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "spi_ss_n" + }, + "target": { + "block": "69dc2722-2a9d-4126-b109-7e31cfea16b6", + "port": "in" + } + }, + { + "source": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "spi_send" + }, + "target": { + "block": "252056ef-9e93-4572-9542-6c05ab5014f3", + "port": "in" + } + }, + { + "source": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "ena_2clk" + }, + "target": { + "block": "a4ff0e57-8710-43bd-84f6-c41eded90435", + "port": "in" + } + }, + { + "source": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "data_spi" + }, + "target": { + "block": "4e2de48f-16d4-4669-be41-bcdd717f6a58", + "port": "in" + }, + "size": 8 + }, + { + "source": { + "block": "a1e8c8a0-be11-4a4d-a19e-f8ee03fa17ae", + "port": "out" + }, + "target": { + "block": "734d9762-f219-4091-8639-8f686819de29", + "port": "clk" + } + } + ] + } + }, + "dependencies": {} +} \ No newline at end of file diff --git a/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.v b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.v new file mode 100644 index 00000000..d4b80cef --- /dev/null +++ b/Blocks/General_Blocks/spi/alhambra_ii/spi_controller/Icestudio/spi_ctrl.v @@ -0,0 +1,435 @@ +////////////////////////////////////////////////////////////////////////////////// +// 12MHz clock +// Receives Motor PWM and leds commands for the GoPiGo3, and send them via SPI +// before sending them, check if there has been any change since the last sending + +module spi_ctrl +( + input rst, + input clk, + input busy_spi, + + input [7:0] motor_pwm_left_i, // left pwm motor ca2: -100 to 100 + input [7:0] motor_pwm_rght_i, // right pwm motor ca2: -100 to 100 + + // led eye left rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + input [24-1:0] led_eye_left_rgb_i, + + // led eye right rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + input [24-1:0] led_eye_rght_rgb_i, + + // led blink left rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + input [24-1:0] led_blink_left_rgb_i, + + // led blink right rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + input [24-1:0] led_blink_rght_rgb_i, + + output reg spi_ss_n, // spi slave select, active low + output reg spi_send, // command to send a new SPI byte + output ena_2clk, // ena spi, twice the frequency + output [7:0] data_spi +); + + // register of the inputs, to check if they have been modified since + // the last update to the SPI + reg [7:0] motor_pwm_left_rg; // 0: left pwm motor ca2: -100 to 100 + reg [7:0] motor_pwm_rght_rg; // 1: right pwm motor ca2: -100 to 100 + + // led eye left rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + reg [24-1:0] led_eye_left_rgb_rg; // 2 + + // led eye right rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + reg [24-1:0] led_eye_rght_rgb_rg; // 3 + + // led blink left rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + reg [24-1:0] led_blink_left_rgb_rg; // 4 + + // led blink right rgb color: 0 to 255 each channel R[23:16] G[15:8] B[7:0] + reg [24-1:0] led_blink_rght_rgb_rg; // 5 + + // Register type + parameter + MOTOR_PWM_LEFT = 0, + MOTOR_PWM_RGHT = 1, + LED_EYE_LEFT = 2, + LED_EYE_RGHT = 3, + LED_BLINK_LEFT = 4, + LED_BLINK_RGHT = 5; + + parameter NUM_RGS = LED_BLINK_RGHT; + // counter to check all the register 0 to 5 + reg [3:0] cnt_chk_rgs; // range depends on NUM_RGS + // indicates if there has been any change in the registers having checked all + // of them + wire cnt_chk_rgs_ended; + // comparison between the input and the last sent command (registered) + reg [32-1:0] compare_port; // input port to compare + reg [32-1:0] compare_reg; // The largest argument so far has 4 bytes + reg any_rg_change; + + integer indx; // for the loop + + // 1: if the new command is the same as the last sent. Depends on the actual + // register that is being compared (cnt_chk_rgs) + wire rg_change; + + // counter for the SPI registers + reg [5:0] cnt_spi_byte; + reg incr_spi_byte; // increment the the SPI byte counter + + // FSM states to send SPI + parameter + CHK_NEW_SPI = 0, // check if there is any new SPI command to be sent + UPDATE_SPI_RGS = 1, // update the SPI registers, to send them + EN_SPI_ST = 2, // to have some time to active the SPI enable + // before sending any command + WAIT_SPI_ST = 3, // wait for the SPI to be ready (not busy) + SPI_SEND_ST = 4, // Send the SPI byte + SPI_SEND2_ST = 5, // wait for the SPI to be busy + EN_SPI2_ST = 6, // keeping the SPI enabled before dissabling it + FINISH_ST = 7; // Finish, and back to 0 + + reg [2:0] spi_state, spi_state_nxt; // present and next state + + // Maximum number of bytes to be sent in a command to SPI + // dont think there are more than 15 bytes to be sent via SPI + parameter N_SPI_BYTES = 16; + reg [8-1:0] spi_bytes [N_SPI_BYTES-1:0]; + parameter NB_SPI_BYTES = $clog2(N_SPI_BYTES); // number of bits + reg [NB_SPI_BYTES-1:0] last_spi_byte; // indicates the last SPI byte to be sent + + // slave select (chip enable) for the SPI of the slave (gopigo) + parameter C_SPI_SS_ON = 1'b0; // active low + parameter C_SPI_SS_OFF = 1'b1; + + reg [3:0] cnt_spi_clk; // count to 12 for the spi clock divider + //wire end_ena_2clk; + reg ena_spi_clk; // enable SPI clk + wire end_cnt_spi_clk; + + // counter that has a variable end of the count + reg [28:0] cnt_var; // to have time before sending the commands + // 25 bits: 33.5 millions -> 12MHz -> ~2.8 segs + wire cnt_var_ended; // indicates the end of the count + //reg [28:0] end_cnt_val; // indicates the value at the count finish + reg ena_cnt_var; // enable of the counter + + //parameter C_STARTUP_END = 2**25-1; // for synthesis + // 12MHz -> 83.3 ns x 33,554,432 -> + // 0,36Hz -> 2,8 s + //parameter C_STARTUP_END = 2**22-1; // for synthesis + // 12MHz -> 83.3 ns x 4,192,304 -> + // 2,86Hz -> 349ms + //parameter C_STARTUP_END = 1500-1; // for simulation + + //parameter C_EN_SPI_END = 2**20-1; // for synthesis + // 12MHz -> 83.3 ns x 10**6 -> + // 12Hz -> 83.3 ms + //parameter C_EN_SPI_END = 2**16-1; // for synthesis + // 12MHz -> 83.3 ns x 65000 -> + // 183Hz -> 5.5 ms + parameter C_EN_SPI_END = 500-1; // for simulation + + + always @(posedge rst, posedge clk) + begin + if (rst) begin + last_spi_byte <= 0; + spi_bytes[0] <= 8'h08; // SPI address, always first byte to be sent + for (indx=1; indx < N_SPI_BYTES; indx=indx+1) begin + spi_bytes[indx] <= 8'h00; + end + end + else begin + if (spi_state == CHK_NEW_SPI) begin + last_spi_byte <= 0; + spi_bytes[0] <= 8'h08; // SPI address, always first byte to be sent + // all registers to zero + for (indx=1; indx < N_SPI_BYTES; indx=indx+1) begin + spi_bytes[indx] <= 8'h00; + end + end + else if (spi_state == UPDATE_SPI_RGS) begin + case (cnt_chk_rgs) + MOTOR_PWM_LEFT: begin + spi_bytes[1] <= 8'h0A; // SPI Message type SET_MOTOR_PWM + spi_bytes[2] <= 8'h01; // MOTOR_LEFT + spi_bytes[3] <= motor_pwm_left_i; // PWM speed -100 to 100 + last_spi_byte <= 3; + end + MOTOR_PWM_RGHT: begin + spi_bytes[1] <= 8'h0A; // SPI Message type SET_MOTOR_PWM + spi_bytes[2] <= 8'h02; // MOTOR_RIGHT + spi_bytes[3] <= motor_pwm_rght_i; // PWM speed -100 to 100 + last_spi_byte <= 3; + end + LED_EYE_LEFT: begin + spi_bytes[1] <= 8'h06; // SPI Message type SET_LED + spi_bytes[2] <= 8'h02; // LED_EYE_LEFT + spi_bytes[3] <= led_eye_left_rgb_i[23:16]; // Red 0 to 255 + spi_bytes[4] <= led_eye_left_rgb_i[15:8]; // Green 0 to 255 + spi_bytes[5] <= led_eye_left_rgb_i[7:0]; // Blue 0 to 255 + last_spi_byte <= 5; + end + LED_EYE_RGHT: begin + spi_bytes[1] <= 8'h06; // SPI Message type SET_LED + spi_bytes[2] <= 8'h01; // LED_EYE_RIGHT + spi_bytes[3] <= led_eye_rght_rgb_i[23:16]; // Red 0 to 255 + spi_bytes[4] <= led_eye_rght_rgb_i[15:8]; // Green 0 to 255 + spi_bytes[5] <= led_eye_rght_rgb_i[7:0]; // Blue 0 to 255 + last_spi_byte <= 5; + end + LED_BLINK_LEFT: begin + spi_bytes[1] <= 8'h06; // SPI Message type SET_LED + spi_bytes[2] <= 8'h04; // LED_BLINK_LEFT + spi_bytes[3] <= led_blink_left_rgb_i[23:16]; // Red 0 to 255 + spi_bytes[4] <= led_blink_left_rgb_i[15:8]; // Green 0 to 255 + spi_bytes[5] <= led_blink_left_rgb_i[7:0]; // Blue 0 to 255 + last_spi_byte <= 5; + end + LED_BLINK_RGHT: begin + spi_bytes[1] <= 8'h06; // SPI Message type SET_LED + spi_bytes[2] <= 8'h08; // LED_BLINK_RIGHT + spi_bytes[3] <= led_blink_rght_rgb_i[23:16]; // Red 0 to 255 + spi_bytes[4] <= led_blink_rght_rgb_i[15:8]; // Green 0 to 255 + spi_bytes[5] <= led_blink_rght_rgb_i[7:0]; // Blue 0 to 255 + last_spi_byte <= 5; + end + endcase + end + end + end + + // register the new commands that have been sent (are just going to be sent) + always @(posedge rst, posedge clk) + begin + if (rst) begin + motor_pwm_left_rg <= 0; // 0 + motor_pwm_rght_rg <= 0; // 1 + led_eye_left_rgb_rg <= 0; // 2 + led_eye_rght_rgb_rg <= 0; // 3 + led_blink_left_rgb_rg <= 0; // 4 + led_blink_rght_rgb_rg <= 0; // 5 + end + else begin + if (spi_state == UPDATE_SPI_RGS) begin + case (cnt_chk_rgs) + MOTOR_PWM_LEFT: + motor_pwm_left_rg <= motor_pwm_left_i; + MOTOR_PWM_RGHT: + motor_pwm_rght_rg <= motor_pwm_rght_i; + LED_EYE_LEFT: + led_eye_left_rgb_rg <= led_eye_left_rgb_i; + LED_EYE_RGHT: + led_eye_rght_rgb_rg <= led_eye_rght_rgb_i; + LED_BLINK_LEFT: + led_blink_left_rgb_rg <= led_blink_left_rgb_i; + LED_BLINK_RGHT: + led_blink_rght_rgb_rg <= led_blink_rght_rgb_i; + endcase + end + end + end + + + + // counter to check all the registers + + always @(posedge rst, posedge clk) + begin + if (rst) + cnt_chk_rgs <= 0; + else begin + // only counts when checking if there are new SPI commands to be sent + if (spi_state == CHK_NEW_SPI) begin + if (rg_change==1'b0) begin // if no change, check the next one + if (cnt_chk_rgs_ended) + cnt_chk_rgs <= 0; + else + cnt_chk_rgs <= cnt_chk_rgs + 1'b1; + end + end + end + end + + assign cnt_chk_rgs_ended = (cnt_chk_rgs == NUM_RGS) ? 1'b1 : 1'b0; + + // depending on the register to be checked (given by cnt_chk_rgs) + // the register length is different. In order to use just one comparator, we'll + // select the registers and the inputs to be compared + always @(*) + begin + compare_port = 32'b0; + compare_reg = 32'b0; + case (cnt_chk_rgs) + MOTOR_PWM_LEFT: begin // one byte + compare_port[7:0] = motor_pwm_left_i; + compare_reg [7:0] = motor_pwm_left_rg; + end + MOTOR_PWM_RGHT: begin // one byte + compare_port[7:0] = motor_pwm_rght_i; + compare_reg [7:0] = motor_pwm_rght_rg; + end + LED_EYE_LEFT: begin // 3 bytes + compare_port[24-1:0] = led_eye_left_rgb_i; + compare_reg [24-1:0] = led_eye_left_rgb_rg; + end + LED_EYE_RGHT: begin // 3 bytes + compare_port[24-1:0] = led_eye_rght_rgb_i; + compare_reg [24-1:0] = led_eye_rght_rgb_rg; + end + LED_BLINK_LEFT: begin // 3 bytes + compare_port[24-1:0] = led_blink_left_rgb_i; + compare_reg [24-1:0] = led_blink_left_rgb_rg; + end + LED_BLINK_RGHT: begin // 3 bytes + compare_port[24-1:0] = led_blink_rght_rgb_i; + compare_reg [24-1:0] = led_blink_rght_rgb_rg; + end + endcase + end + + // -- compare if the actual command is the same as the last command sent + assign rg_change = (compare_port == compare_reg) ? 1'b0 : 1'b1; + + // -------------- timer (counter) to wait a configurable amount of time + + always @(posedge rst, posedge clk) + begin + if (rst) + cnt_var <= 0; + else begin + if (ena_cnt_var) begin + if (cnt_var_ended) + cnt_var <= 0; + else + cnt_var <= cnt_var + 1'b1; + end + else + cnt_var <= 0; + end + end + + assign cnt_var_ended = (cnt_var == C_EN_SPI_END) ? 1'b1 : 1'b0; + + + // -------------- SPI clock generation ----------------------- + // clk divider. Alhambra clock is 12 MHz, + // from the logic analyzer, SCK is 500 kHz, then ena_2clk has to be 1MHz + // count to 12 + always @(posedge rst, posedge clk) + begin + if (rst) + cnt_spi_clk <= 3'b0; + else begin + if ((end_cnt_spi_clk) || (ena_spi_clk == 1'b0)) + cnt_spi_clk <= 3'b0; + else + cnt_spi_clk <= cnt_spi_clk + 1'b1; + end + end + + // end of the count 0 to 11: 1 MHz signal + assign end_cnt_spi_clk = (cnt_spi_clk == 12-1) ? 1'b1 : 1'b0; + assign ena_2clk = end_cnt_spi_clk; + + + // ------------------- SPI register counter ----------------------- + always @ (posedge rst, posedge clk) + begin + if (rst) + cnt_spi_byte <= 0; + else begin + if (spi_state == CHK_NEW_SPI) + cnt_spi_byte <= 0; + else if (incr_spi_byte) + cnt_spi_byte <= cnt_spi_byte + 1'b1; + end + end + + // --------------- FINITE STATE MACHINE (FSM) ------------ + + // FSM sequential process + always @ (posedge rst, posedge clk) + begin + if (rst) + spi_state <= CHK_NEW_SPI; + else + spi_state <= spi_state_nxt; + end + + // FSM combinational process + always @ (*) + begin + spi_state_nxt = spi_state; // default value + ena_cnt_var = 1'b0; + spi_ss_n = C_SPI_SS_OFF; // disable the slave SPI + incr_spi_byte = 1'b0; + spi_send = 1'b0; + ena_spi_clk = 1'b0; // disable the generation of the SPI clock + case (spi_state) + CHK_NEW_SPI: begin // check if there is a new SPI command + if (rg_change) begin // There is a new SPI command to send + spi_state_nxt = UPDATE_SPI_RGS; // + end + end + UPDATE_SPI_RGS: begin // update the SPI registers + spi_state_nxt = EN_SPI_ST; // + end + EN_SPI_ST: begin // enable the SPI slave, and wait some time + ena_spi_clk = 1'b1; // enable the generation of the SPI clock + spi_ss_n = C_SPI_SS_ON; // enable the slave SPI + ena_cnt_var = 1'b1; + if (cnt_var_ended) begin + spi_state_nxt = SPI_SEND_ST; //SPI shouldnt be busy when just starting + ena_cnt_var = 1'b0; + end + end + WAIT_SPI_ST: begin + ena_spi_clk = 1'b1; // enable the generation of the SPI clock + spi_ss_n = C_SPI_SS_ON; // enable the slave SPI + if (!busy_spi) begin + spi_state_nxt = SPI_SEND_ST; + if (cnt_spi_byte == last_spi_byte) + spi_state_nxt = EN_SPI2_ST; // we are done + else // next byte + incr_spi_byte = 1'b1; // increment the byte except when 1 + end + end + SPI_SEND_ST: begin // send the new byte + ena_spi_clk = 1'b1; // enable the generation of the SPI clock + spi_ss_n = C_SPI_SS_ON; // enable the slave SPI + spi_send = 1'b1; + spi_state_nxt = SPI_SEND2_ST; + end + SPI_SEND2_ST: begin // to give time for the SPI to be busy + ena_spi_clk = 1'b1; // enable the generation of the SPI clock + spi_ss_n = C_SPI_SS_ON; // enable the slave SPI + spi_send = 1'b0; // the send command was activated in the transition + incr_spi_byte = 1'b0; + if (busy_spi) + spi_state_nxt = WAIT_SPI_ST; + end + EN_SPI2_ST: begin // finishing the transmission, enabling the SPI slave, + // before dissabling it + ena_spi_clk = 1'b1; // enable the generation of the SPI clock + spi_ss_n = C_SPI_SS_ON; // enable the slave SPI + ena_cnt_var = 1'b1; + if (cnt_var_ended) begin + spi_state_nxt = FINISH_ST; + ena_cnt_var = 1'b0; + end + end + FINISH_ST: begin // transmission ended, maybe not necessary and just jump + // to CHK_NEW_SPI + spi_state_nxt = CHK_NEW_SPI; + end + endcase + end + + // the SPI byte to send + assign data_spi = spi_bytes[cnt_spi_byte]; + + + +endmodule