mirror of
https://github.com/supleed2/ELEC50003-P1-CW.git
synced 2024-12-22 21:45:49 +00:00
Merge branch 'main' into PIOjc4419
This commit is contained in:
commit
20f13252a7
2
Control/.gitignore
vendored
2
Control/.gitignore
vendored
|
@ -3,4 +3,4 @@
|
|||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
||||
src/credentials.h
|
||||
include/credentials.h
|
||||
|
|
21
Control/include/instruction.h
Normal file
21
Control/include/instruction.h
Normal file
|
@ -0,0 +1,21 @@
|
|||
#ifndef INSTRUCTION_H
|
||||
#define INSTRUCTION_H
|
||||
|
||||
typedef enum {
|
||||
INSTR_RESET = -1,
|
||||
INSTR_STOP,
|
||||
INSTR_MOVE,
|
||||
INSTR_CHARGE
|
||||
} instr_t;
|
||||
|
||||
typedef struct instruction
|
||||
{
|
||||
int id;
|
||||
int instr;
|
||||
int heading;
|
||||
int distance;
|
||||
float speed;
|
||||
int charge;
|
||||
} RoverInstruction;
|
||||
|
||||
#endif
|
11
Control/include/status.h
Normal file
11
Control/include/status.h
Normal file
|
@ -0,0 +1,11 @@
|
|||
#ifndef CONTROL_STATUS_H
|
||||
#define CONTROL_STATUS_H
|
||||
|
||||
typedef enum {
|
||||
CS_ERROR = -1,
|
||||
CS_IDLE,
|
||||
CS_MOVING,
|
||||
CS_CHARGING
|
||||
} ControlStatus_t;
|
||||
|
||||
#endif
|
44
Control/ref/command.cpp
Normal file
44
Control/ref/command.cpp
Normal file
|
@ -0,0 +1,44 @@
|
|||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
#include <string>
|
||||
|
||||
#define WebSocket 0
|
||||
int state, totalTripDistance, currentHeading, current_x, current_y, signal_strength, lastCompletedCommand_id; // Info Control ==> Command
|
||||
float batteryVoltage, batteryLevel, batteryCycles; // Info Control ==> Command
|
||||
int command_id, mode, reqHeading, reqDistance, reqCharge; // Info Command ==> Control
|
||||
float reqSpeed; // Info Command ==> Control
|
||||
|
||||
void setup() {}
|
||||
|
||||
void loop()
|
||||
{
|
||||
DynamicJsonDocument rdoc(1024); // receive doc, not sure how big this needs to be
|
||||
deserializeJson(rdoc, WebSocket); // Take JSON input from WebSocket
|
||||
state = rdoc["st"]; // State: -1 = Error, 0 = Idle, 1 = Moving, 2 = Charging
|
||||
batteryVoltage = rdoc["bV"];
|
||||
batteryLevel = rdoc["bL"];
|
||||
batteryCycles = rdoc["bC"];
|
||||
totalTripDistance = rdoc["tD"];
|
||||
currentHeading = rdoc["cH"];
|
||||
current_x = rdoc["pos"][0];
|
||||
current_y = rdoc["pos"][1];
|
||||
signal_strength = rdoc["rssi"];
|
||||
lastCompletedCommand_id = rdoc["LCCid"];
|
||||
|
||||
// ResetTelemetry / STOP / M 0 50 1 / C %
|
||||
// [20] Heading: 0, Distance: 50, Speed: 1 / [20] Charging to: ??%
|
||||
// {"Cid":20,"rH":0,}
|
||||
|
||||
DynamicJsonDocument tdoc(1024); // transmit doc, not sure how big this needs to be
|
||||
tdoc["Cid"] = command_id;
|
||||
tdoc["mode"] = mode; // Switch (mode):
|
||||
// -1 = Add to queue, reset x/y/odometer (telemetry data)
|
||||
// 0 = Stop immediately, clear command cache
|
||||
// 1 = Normal movement command, added to end of command cache
|
||||
// 2 = Normal charge command, results in no motion, added to end of command cache
|
||||
tdoc["rH"] = reqHeading;
|
||||
tdoc["rD"] = reqDistance;
|
||||
tdoc["rS"] = reqSpeed;
|
||||
tdoc["rC"] = reqCharge;
|
||||
serializeJson(tdoc, WebSocket, WebSocket); // Build JSON and send on UART1
|
||||
}
|
41
Control/ref/drive.cpp
Normal file
41
Control/ref/drive.cpp
Normal file
|
@ -0,0 +1,41 @@
|
|||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
#include <string>
|
||||
|
||||
#define RXpin 0 // Define your RX pin here
|
||||
#define TXpin 0 // Define your TX pin here
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200); // Set up hardware UART0 (Connected to USB port)
|
||||
Serial1.begin(9600, SERIAL_8N1, RXpin, TXpin); // Set up hardware UART1
|
||||
|
||||
// Other Drive setup stuff
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
DynamicJsonDocument rdoc(1024); // receive doc, not sure how big this needs to be
|
||||
deserializeJson(rdoc, Serial1); // Take JSON input from UART1
|
||||
int requiredHeading = rdoc["rH"]; // if -1: command in progress, returning requested heading, dist/sp to be ignored
|
||||
int distance = rdoc["dist"]; // -1 for emergency stop
|
||||
float spd = rdoc["sp"]; // -1 for emergency stop
|
||||
int currentHeading = rdoc["cH"];
|
||||
bool resetDistanceTravelled = rdoc["rstD"];
|
||||
|
||||
bool commandComplete = 0;
|
||||
float powerUsage_mWh = 0.0;
|
||||
int distTravelled_mm = 0;
|
||||
int current_x = 0;
|
||||
int current_y = 0;
|
||||
|
||||
// Do Drive stuff, set the 5 values above
|
||||
|
||||
DynamicJsonDocument tdoc(1024); // transmit doc, not sure how big this needs to be
|
||||
tdoc["comp"] = commandComplete; // If 0: command in progress, current heading requested
|
||||
tdoc["mWh"] = powerUsage_mWh;
|
||||
tdoc["mm"] = distTravelled_mm;
|
||||
tdoc["pos"][0] = current_x;
|
||||
tdoc["pos"][1] = current_y;
|
||||
serializeJson(tdoc, Serial1); // Build JSON and send on UART1
|
||||
}
|
37
Control/ref/energy.cpp
Normal file
37
Control/ref/energy.cpp
Normal file
|
@ -0,0 +1,37 @@
|
|||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
#include <string>
|
||||
|
||||
#define RXpin 0 // Define your RX pin here
|
||||
#define TXpin 0 // Define your TX pin here
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200); // Set up hardware UART0 (Connected to USB port)
|
||||
Serial1.begin(9600, SERIAL_8N1, RXpin, TXpin); // Set up hardware UART1
|
||||
|
||||
// Other Drive setup stuff
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
bool charge;
|
||||
DynamicJsonDocument rdoc(1024); // receive doc, not sure how big this needs to be
|
||||
if(Serial1.available()){
|
||||
deserializeJson(rdoc, Serial1); // Take JSON input from UART1
|
||||
charge = rdoc["ch"]; // {"ch":0}
|
||||
}
|
||||
|
||||
|
||||
float stateOfCharge = 0;
|
||||
float batteryVoltage = 0;
|
||||
float batteryCycles = 0;
|
||||
|
||||
// Do Drive stuff, set the 5 values above
|
||||
|
||||
DynamicJsonDocument tdoc(1024); // transmit doc, not sure how big this needs to be
|
||||
tdoc["soc"] = stateOfCharge;
|
||||
tdoc["mV"] = batteryVoltage;
|
||||
tdoc["cyc"] = batteryCycles;
|
||||
serializeJson(tdoc, Serial1); // Build JSON and send on UART1
|
||||
}
|
49
Control/ref/vision.cpp
Normal file
49
Control/ref/vision.cpp
Normal file
|
@ -0,0 +1,49 @@
|
|||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
#include <string>
|
||||
|
||||
const int ARDUINO_IO[16] = {-1/*RX*/, -1/*RX*/, 23, 22, 21, 19, 18, 5, 17, 16, 14, 4, 15, 2, 13, 12}; // Expansion board mapping
|
||||
#define RXpin ARDUINO_IO[11] // Define your RX pin here
|
||||
#define TXpin ARDUINO_IO[10] // Define your TX pin here
|
||||
FILE* SerialUART;
|
||||
|
||||
void setup()
|
||||
{
|
||||
Serial.begin(115200); // Set up hardware UART0 (Connected to USB port)
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
int command = getc(SerialUART);
|
||||
// command char, used for controlling exposure/focus/gain settings:
|
||||
// e = increase exposure
|
||||
// d = decrease exposure
|
||||
// r = increase focus
|
||||
// f = decrease focus
|
||||
// t = increase gain
|
||||
// g = decrease gain
|
||||
|
||||
// Bounding Box edges
|
||||
int bb_left = 0;
|
||||
int bb_right = 0;
|
||||
int bb_top = 0;
|
||||
int bb_bottom = 0;
|
||||
// Weighted average of detected pixels coordinates
|
||||
int centre_x = 0;
|
||||
int centre_y = 0;
|
||||
// Heading from DE10-Lite magnetometer
|
||||
float heading = 0.0;
|
||||
|
||||
// Build hardcode JSON packet on DE10-Lite using fprintf() as space is minimal and library would be too large.
|
||||
// fprintf(SerialUART, "{\"bb\":[%d,%d,%d,%d],\"cen\":[%d,%d],\"cH\":%d\"}", bb_left, bb_right, bb_top, bb_bottom, centre_x, centre_y, heading);
|
||||
|
||||
DynamicJsonDocument rdoc(1024); // receive doc, not sure how big this needs to be
|
||||
deserializeJson(rdoc, SerialUART);
|
||||
bb_left = rdoc["bb"][0];
|
||||
bb_right = rdoc["bb"][1];
|
||||
bb_top = rdoc["bb"][2];
|
||||
bb_bottom = rdoc["bb"][3];
|
||||
centre_x = rdoc["cen"][0];
|
||||
centre_y = rdoc["cen"][1];
|
||||
heading = rdoc["cH"];
|
||||
}
|
|
@ -1,37 +1,73 @@
|
|||
#pragma region Includes
|
||||
#include <Arduino.h>
|
||||
#include <string>
|
||||
// #include <SoftwareSerial.h> Software Serial not currently needed
|
||||
#include <SoftwareSerial.h> // Software Serial not currently needed
|
||||
#include <SoftwareSerial.h>
|
||||
#include <AsyncTCP.h>
|
||||
#include <ESPAsyncWebServer.h>
|
||||
#include <ESPmDNS.h>
|
||||
#include "TickerV2.h"
|
||||
#include <WebSocketsServer.h>
|
||||
#include <credentials.h>
|
||||
#include "credentials.h"
|
||||
#include <ArduinoJson.h>
|
||||
#include <SPIFFS.h>
|
||||
#include "status.h"
|
||||
#include "instruction.h"
|
||||
#include <queue>
|
||||
#pragma endregion
|
||||
|
||||
// Enable extra debugging info
|
||||
#pragma region Enable extra debugging info for ESP32
|
||||
#undef LOG_LOCAL_LEVEL
|
||||
#define LOG_LOCAL_LEVEL ESP_LOG_VERBOSE
|
||||
#include "esp_log.h"
|
||||
#pragma endregion
|
||||
|
||||
#define RX1pin 14 // Pin 10 on expansion board, UART1
|
||||
#define TX1pin 4 // Pin 11 on expansion board, UART1
|
||||
#pragma region Definitions eg pins
|
||||
#define RX1pin 18 // Pin 6 on expansion board, UART1
|
||||
#define TX1pin 5 // Pin 7 on expansion board, UART1
|
||||
#define RX2pin 17 // Pin 8 on expansion board, UART2
|
||||
#define TX2pin 16 // Pin 9 on expansion board, UART2
|
||||
#define RX3pin 14 // Pin 10 on expansion board, UART3
|
||||
#define TX3pin 4 // Pin 11 on expansion board, UART3
|
||||
#pragma endregion
|
||||
|
||||
// Function Declarations
|
||||
void printFPGAoutput();
|
||||
void returnSensorData();
|
||||
#pragma region Function Declarations
|
||||
void notFound(AsyncWebServerRequest *request);
|
||||
void webSocketEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length);
|
||||
void queueInstruction(RoverInstruction instruction);
|
||||
void sendToCommand();
|
||||
void sendToDrive(RoverInstruction instruction);
|
||||
void recvFromDrive();
|
||||
void sendToEnergy(bool instruction);
|
||||
void recvFromEnergy();
|
||||
void sendToVision();
|
||||
void recvFromVision();
|
||||
void emergencyStop();
|
||||
#pragma endregion
|
||||
|
||||
// Global objects
|
||||
#pragma region Global objects
|
||||
AsyncWebServer webserver(80);
|
||||
WebSocketsServer websocketserver(81);
|
||||
Ticker ticker;
|
||||
SoftwareSerial Serial3;
|
||||
std::queue<RoverInstruction> InstrQueue;
|
||||
#pragma endregion
|
||||
|
||||
// Global variables
|
||||
float battery_voltage = 4.0f;
|
||||
int distance_travelled = 0;
|
||||
#pragma region Global variables
|
||||
ControlStatus_t Status;
|
||||
float batteryVoltage;
|
||||
float batteryLevel;
|
||||
float batteryCycles;
|
||||
int odometer;
|
||||
int heading;
|
||||
int xpos, ypos;
|
||||
int signalStrength;
|
||||
int lastExecutedCommand, lastCompletedCommand;
|
||||
bool driveCommandComplete;
|
||||
int bb_left, bb_right, bb_top, bb_bottom;
|
||||
int bb_centre_x, bb_centre_y;
|
||||
float chargeGoal;
|
||||
#pragma endregion
|
||||
|
||||
void setup()
|
||||
{
|
||||
|
@ -40,8 +76,24 @@ void setup()
|
|||
esp_log_level_set("dhcpc", ESP_LOG_INFO); // enable INFO logs from DHCP client
|
||||
|
||||
Serial.begin(115200); // Set up hardware UART0 (Connected to USB port)
|
||||
Serial1.begin(9600, SERIAL_8N1, RX1pin, TX1pin); // Set up hardware UART1
|
||||
// Set up remaining communication ports here (Energy, Drive, Vision)
|
||||
Serial1.begin(9600, SERIAL_8N1, RX1pin, TX1pin); // Set up hardware UART1 (Connected to Drive)
|
||||
Serial2.begin(9600, SERIAL_8N1, RX2pin, TX2pin); // Set up hardware UART2 (Connected to Energy)
|
||||
Serial3.begin(9600, SWSERIAL_8N1, RX3pin, TX3pin); // Set up software UART3 (Connected to Vision)
|
||||
|
||||
// Set global variable startup values
|
||||
Status = CS_IDLE;
|
||||
batteryVoltage = 0;
|
||||
batteryLevel = 0;
|
||||
batteryCycles = 0;
|
||||
odometer = 0;
|
||||
heading = 0;
|
||||
xpos = 0;
|
||||
ypos = 0;
|
||||
signalStrength = 0;
|
||||
lastExecutedCommand = 0;
|
||||
lastCompletedCommand = 0;
|
||||
driveCommandComplete = 1;
|
||||
chargeGoal = 0;
|
||||
|
||||
if (!SPIFFS.begin(true)) // Mount SPIFFS
|
||||
{
|
||||
|
@ -51,11 +103,11 @@ void setup()
|
|||
Serial.println("SPIFFS mounted");
|
||||
|
||||
WiFi.begin(WIFI_SSID, WIFI_PW);
|
||||
while (WiFi.status() != WL_CONNECTED)
|
||||
while (WiFi.status() != WL_CONNECTED) // Wait for ESP32 to connect to AP in "credentials.h"
|
||||
{
|
||||
delay(500);
|
||||
}
|
||||
while (!MDNS.begin("rover"))
|
||||
while (!MDNS.begin("rover")) // Set up mDNS cast at "rover.local/"
|
||||
{
|
||||
Serial.println("Error setting up mDNS, retrying in 5s");
|
||||
delay(5000);
|
||||
|
@ -63,56 +115,118 @@ void setup()
|
|||
Serial.println("mDNS set up, access Control Panel at 'rover.local/'");
|
||||
|
||||
webserver.on("/", HTTP_GET, [](AsyncWebServerRequest *request)
|
||||
{ request->send(SPIFFS, "/index.html", "text/html"); });
|
||||
{ request->send(SPIFFS, "/index.html", "text/html"); }); // Serve "index.html" at root page
|
||||
webserver.on("/favicon.ico", HTTP_GET, [](AsyncWebServerRequest *request)
|
||||
{ request->send(SPIFFS, "/favicon.ico", "image/png"); });
|
||||
webserver.onNotFound(notFound);
|
||||
webserver.begin();
|
||||
{ request->send(SPIFFS, "/favicon.ico", "image/png"); }); // Serve tab icon
|
||||
webserver.onNotFound(notFound); // Set up basic 404NotFound page
|
||||
webserver.begin(); // Start Asynchronous Web Server
|
||||
|
||||
websocketserver.begin();
|
||||
websocketserver.onEvent(webSocketEvent);
|
||||
ticker.attach(0.5, returnSensorData);
|
||||
websocketserver.begin(); // Start Websocket Server
|
||||
websocketserver.onEvent(webSocketEvent); // Set up function call when event received from Command
|
||||
ticker.attach(0.5, sendToCommand); // Set up recurring function to forward rover status to Command
|
||||
}
|
||||
|
||||
void loop()
|
||||
{
|
||||
printFPGAoutput();
|
||||
|
||||
String FPGAinput; // Forward serial monitor input to FPGA
|
||||
if (Serial.available())
|
||||
{
|
||||
FPGAinput = String(Serial.readStringUntil('\n'));
|
||||
Serial1.println(FPGAinput);
|
||||
}
|
||||
|
||||
websocketserver.loop(); // Handle incoming client connections
|
||||
recvFromDrive(); // Update stats from Drive
|
||||
recvFromEnergy(); // Update stats from Energy
|
||||
recvFromVision(); // Update stats from Vision
|
||||
switch (Status)
|
||||
{
|
||||
case CS_ERROR:
|
||||
{
|
||||
Serial.println("Rover in error state, rebooting...");
|
||||
exit(1);
|
||||
}
|
||||
break;
|
||||
case CS_IDLE:
|
||||
{
|
||||
if (!InstrQueue.empty()) // If Rover idle and InstrQueue NOT empty: Do the next command in the queue
|
||||
{
|
||||
RoverInstruction *instr = &InstrQueue.front(); // Get next command
|
||||
switch (instr->instr) // Determine command type
|
||||
{
|
||||
case INSTR_RESET: // Reset telemetry values (zeroing position/distance)
|
||||
{
|
||||
odometer = 0;
|
||||
xpos = 0;
|
||||
ypos = 0;
|
||||
DynamicJsonDocument tdoc(128);
|
||||
tdoc["rstD"] = 1;
|
||||
serializeJson(tdoc, Serial1); // Send reset odometer signal to Drive
|
||||
}
|
||||
break;
|
||||
case INSTR_STOP: // Emergency stop
|
||||
{
|
||||
Status = CS_ERROR;
|
||||
while (1)
|
||||
{
|
||||
Serial.println("Emergency Stop should not get queued, hold and print");
|
||||
delay(1000);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case INSTR_MOVE: // Normal movement
|
||||
{
|
||||
Status = CS_MOVING; // Set moving state
|
||||
driveCommandComplete = 0;
|
||||
sendToDrive(*instr); // Forward to Drive handler
|
||||
}
|
||||
break;
|
||||
case INSTR_CHARGE: // Normal charge
|
||||
{
|
||||
Status = CS_CHARGING; // Set charging state
|
||||
chargeGoal = (float)instr->charge; // Set charging goal
|
||||
sendToEnergy(1); // Forward to Energy handler
|
||||
}
|
||||
break;
|
||||
default:
|
||||
{
|
||||
Serial.println("Unknown instruction type in queue, skipping...");
|
||||
}
|
||||
break;
|
||||
}
|
||||
lastExecutedCommand = instr->id; // Update tracker of last processed command
|
||||
}
|
||||
}
|
||||
break;
|
||||
case CS_MOVING:
|
||||
{
|
||||
if (driveCommandComplete) // If movement command complete:
|
||||
{
|
||||
Status = CS_IDLE; // Set rover state back to idle
|
||||
lastCompletedCommand = lastExecutedCommand; // Update last completed command
|
||||
}
|
||||
else // If movement command NOT complete:
|
||||
{ // Send (up to date) current heading to Drive
|
||||
DynamicJsonDocument tdoc(128);
|
||||
tdoc["rH"] = -1;
|
||||
tdoc["cH"] = heading;
|
||||
serializeJson(tdoc, Serial1);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case CS_CHARGING:
|
||||
{
|
||||
if (batteryLevel >= chargeGoal) // Compare batteryLevel to chargeGoal
|
||||
{
|
||||
Status = CS_IDLE;
|
||||
lastCompletedCommand = lastExecutedCommand; // Update last completed command
|
||||
sendToEnergy(0); // Stop charging if goal reached
|
||||
}
|
||||
// Otherwise continue charging, no change
|
||||
|
||||
void printFPGAoutput()
|
||||
{ // Print serial communication from FPGA to serial monitor
|
||||
String FPGAoutput;
|
||||
if (Serial1.available())
|
||||
{
|
||||
FPGAoutput = String(Serial1.readStringUntil('\n'));
|
||||
Serial.println(FPGAoutput);
|
||||
}
|
||||
}
|
||||
|
||||
void returnSensorData()
|
||||
break;
|
||||
default:
|
||||
{
|
||||
// Collect sensor data here?
|
||||
distance_travelled++;
|
||||
if (battery_voltage < 6)
|
||||
{
|
||||
battery_voltage += 0.2;
|
||||
Serial.println("Unknown rover state, exiting...");
|
||||
exit(1);
|
||||
}
|
||||
else
|
||||
{
|
||||
battery_voltage = 4;
|
||||
break;
|
||||
}
|
||||
String JSON_Data = String("{\"BTRY_VOLT\":") + battery_voltage + String(",\"ODO_DIST\":") + distance_travelled + "}";
|
||||
Serial.println(JSON_Data);
|
||||
websocketserver.broadcastTXT(JSON_Data);
|
||||
delay(500);
|
||||
}
|
||||
|
||||
void notFound(AsyncWebServerRequest *request)
|
||||
|
@ -135,13 +249,13 @@ void webSocketEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length)
|
|||
Serial.printf("Client[%u] Connected from %d.%d.%d.%d url: %s\n", num, ip[0], ip[1], ip[2], ip[3], payload);
|
||||
}
|
||||
break;
|
||||
case WStype_TEXT:
|
||||
case WStype_TEXT: // MSG received from command panel
|
||||
{
|
||||
Serial.printf("Client[%u] sent Text: %s\n", num, payload);
|
||||
String command = String((char *)(payload));
|
||||
Serial.printf("Client[%u] sent Text: %s\n", num, payload); // Echo received command to terminal
|
||||
String command = String((char *)(payload)); // Convert received command to string type
|
||||
|
||||
DynamicJsonDocument doc(200); //creating an instance of a DynamicJsonDocument allocating 200bytes on the heap.
|
||||
DeserializationError error = deserializeJson(doc, command); // deserialize 'doc' and parse for parameters we expect to receive.
|
||||
DynamicJsonDocument rdoc(200); // Create instance of DynamicJsonDocument on heap, 200 Bytes
|
||||
DeserializationError error = deserializeJson(rdoc, command); // Convert command string to JSONDocument and capture any errors
|
||||
if (error)
|
||||
{
|
||||
Serial.print("deserializeJson() failed: ");
|
||||
|
@ -149,12 +263,61 @@ void webSocketEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length)
|
|||
return;
|
||||
}
|
||||
|
||||
int MVM_F_status = doc["MVM_F"];
|
||||
int MVM_L_status = doc["MVM_L"];
|
||||
int MVM_R_status = doc["MVM_R"];
|
||||
int MVM_B_status = doc["MVM_B"];
|
||||
RoverInstruction instr;
|
||||
int mode = rdoc["mode"];
|
||||
switch (mode)
|
||||
{
|
||||
case -1: // Add to queue, reset x/y/odometer (telemetry data)
|
||||
{
|
||||
Serial.println("Reset telemetry command received");
|
||||
instr.id = rdoc["Cid"];
|
||||
instr.instr = INSTR_RESET;
|
||||
// Ignore rdoc["rH"], rdoc["rD"], rdoc["rS"], rdoc["rC"]
|
||||
|
||||
Serial.println('<' + MVM_F_status + ',' + MVM_B_status + ',' + MVM_L_status + ',' + MVM_R_status + '>');
|
||||
queueInstruction(instr); // Put reset command in InstrQueue
|
||||
}
|
||||
break;
|
||||
case 0: // Stop immediately, clear command cache
|
||||
{
|
||||
Serial.println("Emergency stop command received");
|
||||
// instr.instr = INSTR_STOP; // Not needed as Emergency Stop is not queued
|
||||
// Ignore rdoc["Cid"], rdoc["rH"], rdoc["rD"], rdoc["rS"], rdoc["rC"]
|
||||
|
||||
emergencyStop();
|
||||
}
|
||||
break;
|
||||
case 1: // Normal movement command, added to end of command cache
|
||||
{
|
||||
Serial.println("Normal movement command received");
|
||||
instr.id = rdoc["Cid"];
|
||||
instr.instr = INSTR_MOVE;
|
||||
instr.heading = rdoc["rH"];
|
||||
instr.distance = rdoc["rD"];
|
||||
instr.speed = rdoc["rS"];
|
||||
// Ignore rdoc["rC"]
|
||||
|
||||
queueInstruction(instr); // Put movement command in InstrQueue
|
||||
}
|
||||
break;
|
||||
case 2: // Normal charge command, results in no motion, added to end of command cache
|
||||
{
|
||||
Serial.println("Normal charge command received");
|
||||
instr.id = rdoc["Cid"];
|
||||
instr.instr = INSTR_CHARGE;
|
||||
instr.charge = rdoc["rC"];
|
||||
// Ignore rdoc["rH"], rdoc["rD"], rdoc["rS"]
|
||||
|
||||
queueInstruction(instr); // Put charge command in InstrQueue
|
||||
}
|
||||
break;
|
||||
default:
|
||||
{
|
||||
// Default case, print and continue
|
||||
Serial.println("Unknown Command type received, ignoring");
|
||||
// Ignore rdoc["Cid"], rdoc["rH"], rdoc["rD"], rdoc["rS"], rdoc["rC"]
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
break;
|
||||
case WStype_PONG:
|
||||
|
@ -167,5 +330,109 @@ void webSocketEvent(uint8_t num, WStype_t type, uint8_t *payload, size_t length)
|
|||
Serial.println(String("Websocket received invalid event type: ") + type + String(", exiting"));
|
||||
exit(1);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
void queueInstruction(RoverInstruction instruction)
|
||||
{
|
||||
InstrQueue.push(instruction);
|
||||
}
|
||||
|
||||
void sendToCommand()
|
||||
{
|
||||
DynamicJsonDocument tdoc(1024);
|
||||
tdoc["st"] = Status;
|
||||
tdoc["bV"] = batteryVoltage;
|
||||
tdoc["bL"] = batteryLevel;
|
||||
tdoc["bC"] = batteryCycles;
|
||||
tdoc["tD"] = odometer;
|
||||
tdoc["cH"] = heading;
|
||||
tdoc["pos"][0] = xpos;
|
||||
tdoc["pos"][1] = ypos;
|
||||
tdoc["rssi"] = signalStrength;
|
||||
tdoc["LCCid"] = lastCompletedCommand;
|
||||
String JSON_Data;
|
||||
serializeJson(tdoc, JSON_Data);
|
||||
websocketserver.broadcastTXT(JSON_Data);
|
||||
}
|
||||
|
||||
void sendToDrive(RoverInstruction instruction)
|
||||
{
|
||||
DynamicJsonDocument tdoc(1024);
|
||||
tdoc["rH"] = instruction.heading;
|
||||
tdoc["dist"] = instruction.distance;
|
||||
tdoc["sp"] = instruction.speed;
|
||||
tdoc["cH"] = heading;
|
||||
serializeJson(tdoc, Serial1);
|
||||
}
|
||||
|
||||
void recvFromDrive() // Update telemetry data and state info from Drive packet
|
||||
{
|
||||
if (Serial1.available()) // Check for input from UART1 (Connected to Drive)
|
||||
{
|
||||
DynamicJsonDocument rdoc(1024);
|
||||
deserializeJson(rdoc, Serial1);
|
||||
driveCommandComplete = rdoc["comp"];
|
||||
odometer = rdoc["mm"];
|
||||
xpos = rdoc["pos"][0];
|
||||
ypos = rdoc["pos"][1];
|
||||
}
|
||||
}
|
||||
|
||||
void sendToEnergy(bool instruction)
|
||||
{
|
||||
DynamicJsonDocument tdoc(128);
|
||||
tdoc["ch"] = instruction; // Start charging
|
||||
serializeJson(tdoc, Serial2);
|
||||
}
|
||||
|
||||
void recvFromEnergy() // Update telemetry data and state info from Energy packet
|
||||
{
|
||||
if (Serial2.available()) // Check for input from UART2 (Connected to Energy)
|
||||
{
|
||||
DynamicJsonDocument rdoc(1024);
|
||||
deserializeJson(rdoc, Serial2);
|
||||
batteryLevel = rdoc["soc"];
|
||||
batteryVoltage = rdoc["mV"];
|
||||
batteryCycles = rdoc["cyc"];
|
||||
}
|
||||
}
|
||||
|
||||
void sendToVision()
|
||||
{
|
||||
Serial3.print("R"); // Request new data from Vision
|
||||
}
|
||||
|
||||
void recvFromVision() // Update bounding box and obstacle detection data from Vision packet
|
||||
{
|
||||
if (Serial3.available()) // Check for input from UART3 (Connected to Vision)
|
||||
{
|
||||
DynamicJsonDocument rdoc(1024);
|
||||
deserializeJson(rdoc, Serial3);
|
||||
bb_left = rdoc["bb"][0];
|
||||
bb_right = rdoc["bb"][1];
|
||||
bb_top = rdoc["bb"][2];
|
||||
bb_bottom = rdoc["bb"][3];
|
||||
bb_centre_x = rdoc["cen"][0];
|
||||
bb_centre_y = rdoc["cen"][1];
|
||||
heading = rdoc["cH"];
|
||||
}
|
||||
}
|
||||
|
||||
void emergencyStop()
|
||||
{
|
||||
DynamicJsonDocument tdoc(1024);
|
||||
tdoc["rH"] = heading;
|
||||
tdoc["dist"] = -1;
|
||||
tdoc["sp"] = -1;
|
||||
tdoc["cH"] = heading;
|
||||
serializeJson(tdoc, Serial1); // Send stop signals to Drive
|
||||
sendToEnergy(0); // Send stop signal to Energy
|
||||
while (InstrQueue.size())
|
||||
{
|
||||
InstrQueue.pop(); // Clear Instruction Queue
|
||||
}
|
||||
Status = CS_IDLE; // Reset rover to idle state
|
||||
Serial.println("Instruction Queue cleared");
|
||||
}
|
5
Drive/.gitignore
vendored
Normal file
5
Drive/.gitignore
vendored
Normal file
|
@ -0,0 +1,5 @@
|
|||
.pio
|
||||
.vscode/.browse.c_cpp.db*
|
||||
.vscode/c_cpp_properties.json
|
||||
.vscode/launch.json
|
||||
.vscode/ipch
|
7
Drive/.vscode/extensions.json
vendored
Normal file
7
Drive/.vscode/extensions.json
vendored
Normal file
|
@ -0,0 +1,7 @@
|
|||
{
|
||||
// See http://go.microsoft.com/fwlink/?LinkId=827846
|
||||
// for the documentation about the extensions.json format
|
||||
"recommendations": [
|
||||
"platformio.platformio-ide"
|
||||
]
|
||||
}
|
39
Drive/include/README
Normal file
39
Drive/include/README
Normal file
|
@ -0,0 +1,39 @@
|
|||
|
||||
This directory is intended for project header files.
|
||||
|
||||
A header file is a file containing C declarations and macro definitions
|
||||
to be shared between several project source files. You request the use of a
|
||||
header file in your project source file (C, C++, etc) located in `src` folder
|
||||
by including it, with the C preprocessing directive `#include'.
|
||||
|
||||
```src/main.c
|
||||
|
||||
#include "header.h"
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
```
|
||||
|
||||
Including a header file produces the same results as copying the header file
|
||||
into each source file that needs it. Such copying would be time-consuming
|
||||
and error-prone. With a header file, the related declarations appear
|
||||
in only one place. If they need to be changed, they can be changed in one
|
||||
place, and programs that include the header file will automatically use the
|
||||
new version when next recompiled. The header file eliminates the labor of
|
||||
finding and changing all the copies as well as the risk that a failure to
|
||||
find one copy will result in inconsistencies within a program.
|
||||
|
||||
In C, the usual convention is to give header files names that end with `.h'.
|
||||
It is most portable to use only letters, digits, dashes, and underscores in
|
||||
header file names, and at most one dot.
|
||||
|
||||
Read more about using header files in official GCC documentation:
|
||||
|
||||
* Include Syntax
|
||||
* Include Operation
|
||||
* Once-Only Headers
|
||||
* Computed Includes
|
||||
|
||||
https://gcc.gnu.org/onlinedocs/cpp/Header-Files.html
|
46
Drive/lib/README
Normal file
46
Drive/lib/README
Normal file
|
@ -0,0 +1,46 @@
|
|||
|
||||
This directory is intended for project specific (private) libraries.
|
||||
PlatformIO will compile them to static libraries and link into executable file.
|
||||
|
||||
The source code of each library should be placed in a an own separate directory
|
||||
("lib/your_library_name/[here are source files]").
|
||||
|
||||
For example, see a structure of the following two libraries `Foo` and `Bar`:
|
||||
|
||||
|--lib
|
||||
| |
|
||||
| |--Bar
|
||||
| | |--docs
|
||||
| | |--examples
|
||||
| | |--src
|
||||
| | |- Bar.c
|
||||
| | |- Bar.h
|
||||
| | |- library.json (optional, custom build options, etc) https://docs.platformio.org/page/librarymanager/config.html
|
||||
| |
|
||||
| |--Foo
|
||||
| | |- Foo.c
|
||||
| | |- Foo.h
|
||||
| |
|
||||
| |- README --> THIS FILE
|
||||
|
|
||||
|- platformio.ini
|
||||
|--src
|
||||
|- main.c
|
||||
|
||||
and a contents of `src/main.c`:
|
||||
```
|
||||
#include <Foo.h>
|
||||
#include <Bar.h>
|
||||
|
||||
int main (void)
|
||||
{
|
||||
...
|
||||
}
|
||||
|
||||
```
|
||||
|
||||
PlatformIO Library Dependency Finder will find automatically dependent
|
||||
libraries scanning project source files.
|
||||
|
||||
More information about PlatformIO Library Dependency Finder
|
||||
- https://docs.platformio.org/page/librarymanager/ldf.html
|
21
Drive/platformio.ini
Normal file
21
Drive/platformio.ini
Normal file
|
@ -0,0 +1,21 @@
|
|||
; PlatformIO Project Configuration File
|
||||
;
|
||||
; Build options: build flags, source filter
|
||||
; Upload options: custom upload port, speed and extra flags
|
||||
; Library options: dependencies, extra library storages
|
||||
; Advanced options: extra scripting
|
||||
;
|
||||
; Please visit documentation for the other options and examples
|
||||
; https://docs.platformio.org/page/projectconf.html
|
||||
|
||||
[env]
|
||||
lib_deps =
|
||||
bblanchon/ArduinoJson @ ^6.18.0
|
||||
wollewald/INA219_WE @ ^1.1.6
|
||||
monitor_speed = 115200
|
||||
upload_speed = 115200
|
||||
|
||||
[env:nano_every]
|
||||
platform = atmelmegaavr
|
||||
board = nano_every
|
||||
framework = arduino
|
873
Drive/src/main.cpp
Normal file
873
Drive/src/main.cpp
Normal file
|
@ -0,0 +1,873 @@
|
|||
#include <Arduino.h>
|
||||
#include <ArduinoJson.h>
|
||||
// #include <string>
|
||||
#include <Wire.h>
|
||||
#include <INA219_WE.h>
|
||||
#include "SPI.h"
|
||||
#include <SoftwareSerial.h>
|
||||
|
||||
// #define RXpin 4 // Define your RX pin here
|
||||
// #define TXpin 13 // Define your TX pin here
|
||||
|
||||
// SoftwareSerial mySerial(RXpin, TXpin);
|
||||
|
||||
bool debug = false;
|
||||
|
||||
//TO IMPLEMENT
|
||||
//DONE 2 way serial
|
||||
//DONE F<>,B<>,S,L<>,R<>,p<0--1023>
|
||||
//DONE Obtain current and power usage, get voltage from analog pin
|
||||
//request angle facing
|
||||
//DONE speed control 0-1
|
||||
//speed calibration, 0 stop and max speed to match
|
||||
//distance travveled and x and y at request
|
||||
|
||||
//-------------------------------------------------------SMPS & MOTOR CODE START------------------------------------------------------//
|
||||
INA219_WE ina219; // this is the instantiation of the library for the current sensor
|
||||
|
||||
float open_loop, closed_loop; // Duty Cycles
|
||||
float vpd, vb, vref, iL, dutyref, current_mA; // Measurement Variables
|
||||
unsigned int sensorValue0, sensorValue1, sensorValue2, sensorValue3; // ADC sample values declaration
|
||||
float ev = 0, cv = 0, ei = 0, oc = 0; //internal signals
|
||||
float Ts = 0.0008; //1.25 kHz control frequency. It's better to design the control period as integral multiple of switching period.
|
||||
float kpv = 0.05024, kiv = 15.78, kdv = 0; // voltage pid.
|
||||
float u0v, u1v, delta_uv, e0v, e1v, e2v; // u->output; e->error; 0->this time; 1->last time; 2->last last time
|
||||
float kpi = 0.02512, kii = 39.4, kdi = 0; // current pid.
|
||||
float u0i, u1i, delta_ui, e0i, e1i, e2i; // Internal values for the current controller
|
||||
float uv_max = 4, uv_min = 0; //anti-windup limitation
|
||||
float ui_max = 1, ui_min = 0; //anti-windup limitation
|
||||
float current_limit = 1.0;
|
||||
boolean Boost_mode = 0;
|
||||
boolean CL_mode = 0;
|
||||
|
||||
unsigned int loopTrigger;
|
||||
unsigned int com_count = 0; // a variables to count the interrupts. Used for program debugging.
|
||||
|
||||
//************************** Motor Constants **************************//
|
||||
unsigned long previousMillis = 0; //initializing time counter
|
||||
const long f_i = 10000; //time to move in forward direction, please calculate the precision and conversion factor
|
||||
const long r_i = 20000; //time to rotate clockwise
|
||||
const long b_i = 30000; //time to move backwards
|
||||
const long l_i = 40000; //time to move anticlockwise
|
||||
const long s_i = 50000;
|
||||
int DIRRstate = LOW; //initializing direction states
|
||||
int DIRLstate = HIGH;
|
||||
|
||||
int DIRL = 20; //defining left direction pin
|
||||
int DIRR = 21; //defining right direction pin
|
||||
|
||||
int pwmr = 5; //pin to control right wheel speed using pwm
|
||||
int pwml = 9; //pin to control left wheel speed using pwm
|
||||
//*******************************************************************//
|
||||
//-------------------------------------------------------SMPS & MOTOR CODE END------------------------------------------------------//
|
||||
|
||||
//-------------------------------------------------------OPTICAL SENSOR CODE START------------------------------------------------------//
|
||||
#define PIN_SS 10
|
||||
#define PIN_MISO 12
|
||||
#define PIN_MOSI 11
|
||||
#define PIN_SCK 13
|
||||
|
||||
#define PIN_MOUSECAM_RESET 8
|
||||
#define PIN_MOUSECAM_CS 7
|
||||
|
||||
#define ADNS3080_PIXELS_X 30
|
||||
#define ADNS3080_PIXELS_Y 30
|
||||
|
||||
#define ADNS3080_PRODUCT_ID 0x00
|
||||
#define ADNS3080_REVISION_ID 0x01
|
||||
#define ADNS3080_MOTION 0x02
|
||||
#define ADNS3080_DELTA_X 0x03
|
||||
#define ADNS3080_DELTA_Y 0x04
|
||||
#define ADNS3080_SQUAL 0x05
|
||||
#define ADNS3080_PIXEL_SUM 0x06
|
||||
#define ADNS3080_MAXIMUM_PIXEL 0x07
|
||||
#define ADNS3080_CONFIGURATION_BITS 0x0a
|
||||
#define ADNS3080_EXTENDED_CONFIG 0x0b
|
||||
#define ADNS3080_DATA_OUT_LOWER 0x0c
|
||||
#define ADNS3080_DATA_OUT_UPPER 0x0d
|
||||
#define ADNS3080_SHUTTER_LOWER 0x0e
|
||||
#define ADNS3080_SHUTTER_UPPER 0x0f
|
||||
#define ADNS3080_FRAME_PERIOD_LOWER 0x10
|
||||
#define ADNS3080_FRAME_PERIOD_UPPER 0x11
|
||||
#define ADNS3080_MOTION_CLEAR 0x12
|
||||
#define ADNS3080_FRAME_CAPTURE 0x13
|
||||
#define ADNS3080_SROM_ENABLE 0x14
|
||||
#define ADNS3080_FRAME_PERIOD_MAX_BOUND_LOWER 0x19
|
||||
#define ADNS3080_FRAME_PERIOD_MAX_BOUND_UPPER 0x1a
|
||||
#define ADNS3080_FRAME_PERIOD_MIN_BOUND_LOWER 0x1b
|
||||
#define ADNS3080_FRAME_PERIOD_MIN_BOUND_UPPER 0x1c
|
||||
#define ADNS3080_SHUTTER_MAX_BOUND_LOWER 0x1e
|
||||
#define ADNS3080_SHUTTER_MAX_BOUND_UPPER 0x1e
|
||||
#define ADNS3080_SROM_ID 0x1f
|
||||
#define ADNS3080_OBSERVATION 0x3d
|
||||
#define ADNS3080_INVERSE_PRODUCT_ID 0x3f
|
||||
#define ADNS3080_PIXEL_BURST 0x40
|
||||
#define ADNS3080_MOTION_BURST 0x50
|
||||
#define ADNS3080_SROM_LOAD 0x60
|
||||
|
||||
#define ADNS3080_PRODUCT_ID_VAL 0x17
|
||||
|
||||
int total_x = 0;
|
||||
int total_y = 0;
|
||||
|
||||
int total_x1 = 0;
|
||||
int total_y1 = 0;
|
||||
|
||||
int x = 0;
|
||||
int y = 0;
|
||||
|
||||
int a = 0;
|
||||
int b = 0;
|
||||
|
||||
int distance_x = 0;
|
||||
int distance_y = 0;
|
||||
|
||||
int dist_to_move_prev_fl = 0;
|
||||
int dist_to_move_prev_fr = 0;
|
||||
unsigned long time_pid_prev_fl = 0;
|
||||
unsigned long time_pid_prev_fr = 0;
|
||||
|
||||
int dist_to_move_prev_sl = 0;
|
||||
int dist_to_move_prev_sr = 0;
|
||||
unsigned long time_pid_prev_sl = 0;
|
||||
unsigned long time_pid_prev_sr = 0;
|
||||
|
||||
float kpdrive = 0.055;
|
||||
float kddrive = 4.700;
|
||||
|
||||
float kpheading = 0.055;
|
||||
float kdheading = 4.700;
|
||||
|
||||
volatile byte movementflag = 0;
|
||||
volatile int xydat[2];
|
||||
|
||||
// FUNCTION DELCARATIONS //
|
||||
|
||||
float pidi(float pid_input);
|
||||
float pidv(float pid_input);
|
||||
void pwm_modulate(float pwm_input);
|
||||
float saturation(float sat_input, float uplim, float lowlim);
|
||||
void sampling();
|
||||
void mousecam_write_reg(int reg, int val);
|
||||
int mousecam_read_reg(int reg);
|
||||
void mousecam_reset();
|
||||
int getCurrentHeading();
|
||||
float pid_ms(int dist_to_move, int *dist_to_move_prev, unsigned long *time_pid_prev, float kps, float kds);
|
||||
float pid_h_ms(bool left, float speed, int dist_to_move, int *dist_to_move_prev, unsigned long *time_pid_prev, float kps, float kds);
|
||||
|
||||
int convTwosComp(int b)
|
||||
{
|
||||
//Convert from 2's complement
|
||||
if (b & 0x80)
|
||||
{
|
||||
b = -1 * ((b ^ 0xff) + 1);
|
||||
}
|
||||
return b;
|
||||
}
|
||||
|
||||
int tdistance = 0;
|
||||
|
||||
void mousecam_reset(){
|
||||
digitalWrite(PIN_MOUSECAM_RESET, HIGH);
|
||||
delay(1); // reset pulse >10us
|
||||
digitalWrite(PIN_MOUSECAM_RESET, LOW);
|
||||
delay(35); // 35ms from reset to functional
|
||||
}
|
||||
|
||||
int mousecam_init(){
|
||||
pinMode(PIN_MOUSECAM_RESET, OUTPUT);
|
||||
pinMode(PIN_MOUSECAM_CS, OUTPUT);
|
||||
|
||||
digitalWrite(PIN_MOUSECAM_CS, HIGH);
|
||||
|
||||
mousecam_reset();
|
||||
|
||||
int pid = mousecam_read_reg(ADNS3080_PRODUCT_ID);
|
||||
if (pid != ADNS3080_PRODUCT_ID_VAL)
|
||||
return -1;
|
||||
|
||||
// turn on sensitive mode
|
||||
mousecam_write_reg(ADNS3080_CONFIGURATION_BITS, 0x19);
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
void mousecam_write_reg(int reg, int val){
|
||||
digitalWrite(PIN_MOUSECAM_CS, LOW);
|
||||
SPI.transfer(reg | 0x80);
|
||||
SPI.transfer(val);
|
||||
digitalWrite(PIN_MOUSECAM_CS, HIGH);
|
||||
delayMicroseconds(50);
|
||||
}
|
||||
|
||||
int mousecam_read_reg(int reg){
|
||||
digitalWrite(PIN_MOUSECAM_CS, LOW);
|
||||
SPI.transfer(reg);
|
||||
delayMicroseconds(75);
|
||||
int ret = SPI.transfer(0xff);
|
||||
digitalWrite(PIN_MOUSECAM_CS, HIGH);
|
||||
delayMicroseconds(1);
|
||||
return ret;
|
||||
}
|
||||
|
||||
struct MD{
|
||||
byte motion;
|
||||
char dx, dy;
|
||||
byte squal;
|
||||
word shutter;
|
||||
byte max_pix;
|
||||
};
|
||||
|
||||
void mousecam_read_motion(struct MD *p){
|
||||
digitalWrite(PIN_MOUSECAM_CS, LOW);
|
||||
SPI.transfer(ADNS3080_MOTION_BURST);
|
||||
delayMicroseconds(75);
|
||||
p->motion = SPI.transfer(0xff);
|
||||
p->dx = SPI.transfer(0xff);
|
||||
p->dy = SPI.transfer(0xff);
|
||||
p->squal = SPI.transfer(0xff);
|
||||
p->shutter = SPI.transfer(0xff) << 8;
|
||||
p->shutter |= SPI.transfer(0xff);
|
||||
p->max_pix = SPI.transfer(0xff);
|
||||
digitalWrite(PIN_MOUSECAM_CS, HIGH);
|
||||
delayMicroseconds(5);
|
||||
}
|
||||
|
||||
// pdata must point to an array of size ADNS3080_PIXELS_X x ADNS3080_PIXELS_Y
|
||||
// you must call mousecam_reset() after this if you want to go back to normal operation
|
||||
int mousecam_frame_capture(byte *pdata)
|
||||
{
|
||||
mousecam_write_reg(ADNS3080_FRAME_CAPTURE, 0x83);
|
||||
|
||||
digitalWrite(PIN_MOUSECAM_CS, LOW);
|
||||
|
||||
SPI.transfer(ADNS3080_PIXEL_BURST);
|
||||
delayMicroseconds(50);
|
||||
|
||||
int pix;
|
||||
byte started = 0;
|
||||
int count;
|
||||
int timeout = 0;
|
||||
int ret = 0;
|
||||
for (count = 0; count < ADNS3080_PIXELS_X * ADNS3080_PIXELS_Y;)
|
||||
{
|
||||
pix = SPI.transfer(0xff);
|
||||
delayMicroseconds(10);
|
||||
if (started == 0)
|
||||
{
|
||||
if (pix & 0x40)
|
||||
started = 1;
|
||||
else
|
||||
{
|
||||
timeout++;
|
||||
if (timeout == 100)
|
||||
{
|
||||
ret = -1;
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (started == 1)
|
||||
{
|
||||
pdata[count++] = (pix & 0x3f) << 2; // scale to normal grayscale byte range
|
||||
}
|
||||
}
|
||||
|
||||
digitalWrite(PIN_MOUSECAM_CS, HIGH);
|
||||
delayMicroseconds(14);
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
//-------------------------------------------------------OPTICAL SENSOR CODE END------------------------------------------------------//
|
||||
|
||||
//Tracker Variables
|
||||
int current_x = 0;
|
||||
int current_y = 0;
|
||||
int goal_x = 0;
|
||||
int goal_y = 0;
|
||||
int distanceGoal;
|
||||
bool commandComplete = 1;
|
||||
float powerUsage_mWh = 0;
|
||||
int distTravelled_mm = 0;
|
||||
bool initialAngleSet = false;
|
||||
|
||||
//calibration varibles
|
||||
int angularDrift = 0; //+ve to right, -ve to left
|
||||
int leftStart = 80; //pwm min for left motor
|
||||
int leftStop = 255; //pwm max for left motor
|
||||
int rightStart = 80; //pwm min for right motor
|
||||
int rightStop = 255; //pwm max for right motor
|
||||
|
||||
//Energy Usage Variables
|
||||
unsigned long previousMillis_Energy = 0; // will store last time energy use was updated
|
||||
const long interval_Energy = 1000; //energy usaged update frequency
|
||||
float totalEnergyUsed = 0;
|
||||
float powerUsed = 0;
|
||||
int loopCount = 0;
|
||||
float motorVoltage = 0;
|
||||
|
||||
int getPWMfromSpeed(float speedr, bool left)
|
||||
{
|
||||
if (speedr >= 1)
|
||||
{
|
||||
return 512;
|
||||
}
|
||||
else if (speedr < 0)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
else
|
||||
{
|
||||
int speedpercentage = (speedr * 100);
|
||||
if (left)
|
||||
{
|
||||
return map(speedpercentage, 0, 100, leftStart, leftStop);
|
||||
}
|
||||
else
|
||||
{
|
||||
return map(speedpercentage, 0, 100, rightStart, rightStop);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void setup()
|
||||
{
|
||||
//-------------------------------------------------------SMPS & MOTOR CODE START------------------------------------------------------//
|
||||
//************************** Motor Pins Defining **************************//
|
||||
pinMode(DIRR, OUTPUT);
|
||||
pinMode(DIRL, OUTPUT);
|
||||
pinMode(pwmr, OUTPUT);
|
||||
pinMode(pwml, OUTPUT);
|
||||
digitalWrite(pwmr, HIGH); //setting right motor speed at maximum
|
||||
digitalWrite(pwml, HIGH); //setting left motor speed at maximum
|
||||
//*******************************************************************//
|
||||
|
||||
//Basic pin setups
|
||||
|
||||
noInterrupts(); //disable all interrupts
|
||||
pinMode(13, OUTPUT); //Pin13 is used to time the loops of the controller
|
||||
pinMode(3, INPUT_PULLUP); //Pin3 is the input from the Buck/Boost switch
|
||||
pinMode(2, INPUT_PULLUP); // Pin 2 is the input from the CL/OL switch
|
||||
analogReference(EXTERNAL); // We are using an external analogue reference for the ADC
|
||||
|
||||
// TimerA0 initialization for control-loop interrupt.
|
||||
|
||||
TCA0.SINGLE.PER = 999; //
|
||||
TCA0.SINGLE.CMP1 = 999; //
|
||||
TCA0.SINGLE.CTRLA = TCA_SINGLE_CLKSEL_DIV16_gc | TCA_SINGLE_ENABLE_bm; //16 prescaler, 1M.
|
||||
TCA0.SINGLE.INTCTRL = TCA_SINGLE_CMP1_bm;
|
||||
|
||||
// TimerB0 initialization for PWM output
|
||||
|
||||
pinMode(6, OUTPUT);
|
||||
TCB0.CTRLA = TCB_CLKSEL_CLKDIV1_gc | TCB_ENABLE_bm; //62.5kHz
|
||||
analogWrite(6, 120);
|
||||
|
||||
interrupts(); //enable interrupts.
|
||||
Wire.begin(); // We need this for the i2c comms for the current sensor
|
||||
ina219.init(); // this initiates the current sensor
|
||||
Wire.setClock(700000); // set the comms speed for i2c
|
||||
//-------------------------------------------------------SMPS & MOTOR CODE END------------------------------------------------------//
|
||||
Serial.begin(115200); // Set up hardware UART0 (Connected to USB port)
|
||||
Serial1.begin(9600); // Set up hardware UART
|
||||
|
||||
//Serial.println(getPWMfromSpeed(-1));
|
||||
//Serial.println(getPWMfromSpeed(256));
|
||||
//Serial.println(getPWMfromSpeed(0.5));
|
||||
// Other Drive setup stuff
|
||||
/////////currentHeading = REQUEST HEADING HERE;
|
||||
|
||||
analogWrite(pwmr, 0);
|
||||
analogWrite(pwml, 0);
|
||||
//digitalWrite(DIRR, LOW);
|
||||
//digitalWrite(DIRL, HIGH);
|
||||
|
||||
pinMode(PIN_SS, OUTPUT);
|
||||
pinMode(PIN_MISO, INPUT);
|
||||
pinMode(PIN_MOSI, OUTPUT);
|
||||
pinMode(PIN_SCK, OUTPUT);
|
||||
|
||||
SPI.begin();
|
||||
SPI.setClockDivider(SPI_CLOCK_DIV32);
|
||||
SPI.setDataMode(SPI_MODE3);
|
||||
SPI.setBitOrder(MSBFIRST);
|
||||
|
||||
if (mousecam_init() == -1)
|
||||
{
|
||||
Serial.println("Mouse cam failed to init");
|
||||
while (1)
|
||||
;
|
||||
}
|
||||
}
|
||||
|
||||
int commandCompletionStatus = 0; //0-No Command, 1-New Command, 2-Command being run, 3-Command Complete
|
||||
int requiredHeading = 0;
|
||||
int distance = 0;
|
||||
float spd = 0;
|
||||
int currentHeading = 0;
|
||||
//reset variables for update on completion
|
||||
|
||||
unsigned long previousMillis_Command = 0;
|
||||
const long interval_Command = 1000;
|
||||
DeserializationError error;
|
||||
|
||||
char asciiart(int k)
|
||||
{
|
||||
static char foo[] = "WX86*3I>!;~:,`. ";
|
||||
return foo[k >> 4];
|
||||
}
|
||||
|
||||
byte frame[ADNS3080_PIXELS_X * ADNS3080_PIXELS_Y];
|
||||
DynamicJsonDocument rdoc(1024);
|
||||
|
||||
void loop()
|
||||
{
|
||||
if (Serial1.available() && (commandCompletionStatus == 0)){
|
||||
// receive doc, not sure how big this needs to be
|
||||
error = deserializeJson(rdoc, Serial1);
|
||||
|
||||
Serial.println("Got serial");
|
||||
|
||||
// Test if parsing succeeds.
|
||||
if (error)
|
||||
{
|
||||
//Serial.print(F("deserializeJson() failed: "));
|
||||
//Serial.println(error.f_str());
|
||||
return;
|
||||
}
|
||||
else
|
||||
{
|
||||
//parsing success, prepare command and pull request information
|
||||
commandCompletionStatus = 1;
|
||||
requiredHeading = rdoc["rH"];
|
||||
distance = rdoc["dist"];
|
||||
spd = rdoc["sp"];
|
||||
currentHeading = rdoc["cH"];
|
||||
|
||||
Serial.println("rH = " + String(requiredHeading) + " dist = " + String(distance) + " speed = " + String(spd));
|
||||
|
||||
//reset variables for update on completion
|
||||
commandComplete = 0;
|
||||
powerUsage_mWh = 0.0;
|
||||
distTravelled_mm = 0;
|
||||
}
|
||||
}
|
||||
|
||||
//if(current_x!=goal_x)
|
||||
|
||||
// Do Drive stuff, set the 5 values above
|
||||
|
||||
if (commandCompletionStatus == 0)
|
||||
{ //noCommand
|
||||
//Do Nothing just wait
|
||||
//Serial.println("status0");
|
||||
}
|
||||
if (commandCompletionStatus == 1)
|
||||
{ Serial.println("status1");
|
||||
//newCommand
|
||||
//set goals
|
||||
goal_x += distance * sin(requiredHeading);
|
||||
goal_y += distance * cos(requiredHeading);
|
||||
total_y = 0;
|
||||
total_x = 0;
|
||||
commandCompletionStatus = 2;
|
||||
|
||||
initialAngleSet = false;
|
||||
}
|
||||
if (commandCompletionStatus == 2)
|
||||
{ //Serial.println("status2");
|
||||
//ongoingCommand
|
||||
//start moving towards goal
|
||||
|
||||
//set angle first
|
||||
if (!initialAngleSet)
|
||||
{
|
||||
//turn to angle
|
||||
currentHeading = getCurrentHeading();
|
||||
if (currentHeading < requiredHeading)
|
||||
{ //turn right
|
||||
Serial.println("turning right");
|
||||
analogWrite(pwmr, getPWMfromSpeed(spd, false));
|
||||
analogWrite(pwml, getPWMfromSpeed(spd, true));
|
||||
digitalWrite(DIRR, LOW);
|
||||
digitalWrite(DIRL, LOW);
|
||||
}
|
||||
else if (currentHeading > requiredHeading)
|
||||
{ //turn left
|
||||
Serial.println("turning left");
|
||||
analogWrite(pwmr, getPWMfromSpeed(spd, false));
|
||||
analogWrite(pwml, getPWMfromSpeed(spd, true));
|
||||
digitalWrite(DIRR, HIGH);
|
||||
digitalWrite(DIRL, HIGH);
|
||||
}
|
||||
else
|
||||
{
|
||||
//heading correct therefore move to next step...
|
||||
//STOP!!!!
|
||||
digitalWrite(pwmr, LOW);
|
||||
digitalWrite(pwml, LOW);
|
||||
|
||||
initialAngleSet = true;
|
||||
}
|
||||
}
|
||||
else
|
||||
{ //then move forwards but check angle for drift using optical flow
|
||||
if (total_y - distance < 0)
|
||||
{ //go forwards
|
||||
//Serial.println("going forwards");
|
||||
float speed_r = pid_ms(abs(total_y - distance), &dist_to_move_prev_fr, &time_pid_prev_fr, kpdrive, kddrive);
|
||||
float speed_l = pid_ms(abs(total_y - distance), &dist_to_move_prev_fl, &time_pid_prev_fl, kpdrive, kddrive);
|
||||
float speed_r_head = pid_h_ms(0, speed_r, -total_x, &dist_to_move_prev_sr, &time_pid_prev_sr, kpheading, kdheading);
|
||||
float speed_l_head = pid_h_ms(1, speed_l, -total_x, &dist_to_move_prev_sl, &time_pid_prev_sl, kpheading, kdheading);
|
||||
analogWrite(pwmr, getPWMfromSpeed(speed_r, false));
|
||||
analogWrite(pwml, getPWMfromSpeed(speed_l, true));
|
||||
digitalWrite(DIRR, LOW);
|
||||
digitalWrite(DIRL, HIGH);
|
||||
}
|
||||
else if (total_y - distance > 0)
|
||||
{ //go backwards
|
||||
//Serial.println("going backwards");
|
||||
float speed_r = pid_ms(abs(total_y - distance), &dist_to_move_prev_fr, &time_pid_prev_fr, kpdrive, kddrive);
|
||||
float speed_l = pid_ms(abs(total_y - distance), &dist_to_move_prev_fl, &time_pid_prev_fl, kpdrive, kddrive);
|
||||
float speed_r_head = pid_h_ms(0, speed_r, -total_x, &dist_to_move_prev_sr, &time_pid_prev_sr, kpheading, kdheading);
|
||||
float speed_l_head = pid_h_ms(1, speed_l, -total_x, &dist_to_move_prev_sl, &time_pid_prev_sl, kpheading, kdheading);
|
||||
analogWrite(pwmr, getPWMfromSpeed(speed_r, false));
|
||||
analogWrite(pwml, getPWMfromSpeed(speed_l, true));
|
||||
digitalWrite(DIRR, HIGH);
|
||||
digitalWrite(DIRL, LOW);
|
||||
}
|
||||
else if ((total_y == distance))
|
||||
{ //distance met
|
||||
//STOP!!!!!
|
||||
digitalWrite(pwmr, LOW);
|
||||
digitalWrite(pwml, LOW);
|
||||
commandCompletionStatus = 3;
|
||||
initialAngleSet = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
if (commandCompletionStatus == 3)
|
||||
{ Serial.println("status3");
|
||||
//currentPosMatchesOrExceedsRequest
|
||||
///finish moving
|
||||
|
||||
//send update via UART
|
||||
|
||||
//prepare feedback variables
|
||||
commandComplete = true;
|
||||
current_x = goal_x;
|
||||
current_y = goal_y;
|
||||
distTravelled_mm += distance;
|
||||
|
||||
//compile energy use
|
||||
unsigned long currentMillis_Energy = millis();
|
||||
|
||||
totalEnergyUsed += (currentMillis_Energy - previousMillis_Energy) * (powerUsed / loopCount) / 1000 / (60 * 60);
|
||||
previousMillis_Energy = currentMillis_Energy;
|
||||
|
||||
if (debug){
|
||||
Serial.print(motorVoltage);
|
||||
Serial.print("Energy Used: ");
|
||||
Serial.print(totalEnergyUsed);
|
||||
Serial.println("mWh");
|
||||
}
|
||||
|
||||
loopCount = 0; //reset counter to zero
|
||||
powerUsed = 0; //reset power usage
|
||||
powerUsage_mWh = totalEnergyUsed;
|
||||
totalEnergyUsed = 0;
|
||||
total_x1 = 0;
|
||||
total_y1 = 0;
|
||||
|
||||
DynamicJsonDocument tdoc(1024); // transmit doc, not sure how big this needs to be
|
||||
tdoc["comp"] = commandComplete;
|
||||
tdoc["mWh"] = powerUsage_mWh;
|
||||
tdoc["mm"] = distTravelled_mm;
|
||||
tdoc["pos"][0] = current_x;
|
||||
tdoc["pos"][1] = current_y;
|
||||
serializeJson(tdoc, Serial); // Build JSON and send on UART1
|
||||
commandCompletionStatus = 0;
|
||||
}
|
||||
|
||||
//Handle power usage
|
||||
//find motor voltage
|
||||
//int motorVSensor = analogRead(A5);
|
||||
//float motorVoltage = motorVSensor * (5.0 / 1023.0);
|
||||
float motorVoltage = 5;
|
||||
|
||||
//find average power
|
||||
|
||||
if (current_mA >= 0){
|
||||
powerUsed += current_mA * motorVoltage;
|
||||
}
|
||||
if (debug){
|
||||
Serial.println(powerUsed);
|
||||
}
|
||||
|
||||
//calculate averages for energy use calculations
|
||||
loopCount += 1; //handle loop quantity for averaging
|
||||
|
||||
//find average current
|
||||
//find average voltage
|
||||
|
||||
//update command/control
|
||||
|
||||
if (movementflag){
|
||||
|
||||
tdistance = tdistance + convTwosComp(xydat[0]);
|
||||
// Serial.println("Distance = " + String(tdistance));
|
||||
movementflag = 0;
|
||||
delay(3);
|
||||
}
|
||||
int val = mousecam_read_reg(ADNS3080_PIXEL_SUM);
|
||||
MD md;
|
||||
mousecam_read_motion(&md);
|
||||
/* for (int i = 0; i < md.squal / 4; i++)
|
||||
Serial.print('*');
|
||||
Serial.print(' ');
|
||||
Serial.print((val * 100) / 351);
|
||||
Serial.print(' ');
|
||||
Serial.print(md.shutter);
|
||||
Serial.print(" (");
|
||||
Serial.print((int)md.dx);
|
||||
Serial.print(',');
|
||||
Serial.print((int)md.dy);
|
||||
Serial.println(')'); */
|
||||
|
||||
// Serial.println(md.max_pix);
|
||||
delay(100);
|
||||
|
||||
distance_x = md.dx; //convTwosComp(md.dx);
|
||||
distance_y = md.dy; //convTwosComp(md.dy);
|
||||
|
||||
total_x1 = (total_x1 + distance_x);
|
||||
total_y1 = (total_y1 + distance_y);
|
||||
|
||||
total_x = 10 * total_x1 / 157; //Conversion from counts per inch to mm (400 counts per inch)
|
||||
total_y = 10 * total_y1 / 157; //Conversion from counts per inch to mm (400 counts per inch)
|
||||
|
||||
Serial.print('\n');
|
||||
|
||||
Serial.println("Distance_x = " + String(total_x));
|
||||
|
||||
Serial.println("Distance_y = " + String(total_y));
|
||||
Serial.print('\n');
|
||||
//-------------------------------------------------------SMPS & MOTOR CODE START------------------------------------------------------//
|
||||
unsigned long currentMillis = millis();
|
||||
if (loopTrigger)
|
||||
{ // This loop is triggered, it wont run unless there is an interrupt
|
||||
|
||||
digitalWrite(13, HIGH); // set pin 13. Pin13 shows the time consumed by each control cycle. It's used for debugging.
|
||||
|
||||
// Sample all of the measurements and check which control mode we are in
|
||||
sampling();
|
||||
CL_mode = digitalRead(3); // input from the OL_CL switch
|
||||
Boost_mode = digitalRead(2); // input from the Buck_Boost switch
|
||||
|
||||
if (Boost_mode)
|
||||
{
|
||||
if (CL_mode)
|
||||
{ //Closed Loop Boost
|
||||
pwm_modulate(1); // This disables the Boost as we are not using this mode
|
||||
}
|
||||
else
|
||||
{ // Open Loop Boost
|
||||
pwm_modulate(1); // This disables the Boost as we are not using this mode
|
||||
}
|
||||
}
|
||||
else
|
||||
{
|
||||
if (CL_mode)
|
||||
{ // Closed Loop Buck
|
||||
// The closed loop path has a voltage controller cascaded with a current controller. The voltage controller
|
||||
// creates a current demand based upon the voltage error. This demand is saturated to give current limiting.
|
||||
// The current loop then gives a duty cycle demand based upon the error between demanded current and measured
|
||||
// current
|
||||
current_limit = 3; // Buck has a higher current limit
|
||||
ev = vref - vb; //voltage error at this time
|
||||
cv = pidv(ev); //voltage pid
|
||||
cv = saturation(cv, current_limit, 0); //current demand saturation
|
||||
ei = cv - iL; //current error
|
||||
closed_loop = pidi(ei); //current pid
|
||||
closed_loop = saturation(closed_loop, 0.99, 0.01); //duty_cycle saturation
|
||||
pwm_modulate(closed_loop); //pwm modulation
|
||||
}
|
||||
else
|
||||
{ // Open Loop Buck
|
||||
current_limit = 3; // Buck has a higher current limit
|
||||
oc = iL - current_limit; // Calculate the difference between current measurement and current limit
|
||||
if (oc > 0)
|
||||
{
|
||||
open_loop = open_loop - 0.001; // We are above the current limit so less duty cycle
|
||||
}
|
||||
else
|
||||
{
|
||||
open_loop = open_loop + 0.001; // We are below the current limit so more duty cycle
|
||||
}
|
||||
open_loop = saturation(open_loop, dutyref, 0.02); // saturate the duty cycle at the reference or a min of 0.01
|
||||
pwm_modulate(open_loop); // and send it out
|
||||
}
|
||||
}
|
||||
// closed loop control path
|
||||
|
||||
digitalWrite(13, LOW); // reset pin13.
|
||||
loopTrigger = 0;
|
||||
}
|
||||
}
|
||||
|
||||
int getCurrentHeading(){
|
||||
int currentAngle = 0; //-------------___<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<<
|
||||
return currentAngle;
|
||||
}
|
||||
|
||||
// Timer A CMP1 interrupt. Every 800us the program enters this interrupt.
|
||||
// This, clears the incoming interrupt flag and triggers the main loop.
|
||||
|
||||
ISR(TCA0_CMP1_vect){
|
||||
TCA0.SINGLE.INTFLAGS |= TCA_SINGLE_CMP1_bm; //clear interrupt flag
|
||||
loopTrigger = 1;
|
||||
}
|
||||
|
||||
// This subroutine processes all of the analogue samples, creating the required values for the main loop
|
||||
|
||||
void sampling(){
|
||||
|
||||
// Make the initial sampling operations for the circuit measurements
|
||||
|
||||
sensorValue0 = analogRead(A0); //sample Vb
|
||||
sensorValue2 = analogRead(A2); //sample Vref
|
||||
sensorValue3 = analogRead(A3); //sample Vpd
|
||||
current_mA = ina219.getCurrent_mA(); // sample the inductor current (via the sensor chip)
|
||||
|
||||
// Process the values so they are a bit more usable/readable
|
||||
// The analogRead process gives a value between 0 and 1023
|
||||
// representing a voltage between 0 and the analogue reference which is 4.096V
|
||||
|
||||
vb = sensorValue0 * (4.096 / 1023.0); // Convert the Vb sensor reading to volts
|
||||
vref = sensorValue2 * (4.096 / 1023.0); // Convert the Vref sensor reading to volts
|
||||
vpd = sensorValue3 * (4.096 / 1023.0); // Convert the Vpd sensor reading to volts
|
||||
|
||||
// The inductor current is in mA from the sensor so we need to convert to amps.
|
||||
// We want to treat it as an input current in the Boost, so its also inverted
|
||||
// For open loop control the duty cycle reference is calculated from the sensor
|
||||
// differently from the Vref, this time scaled between zero and 1.
|
||||
// The boost duty cycle needs to be saturated with a 0.33 minimum to prevent high output voltages
|
||||
|
||||
if (Boost_mode == 1){
|
||||
iL = -current_mA / 1000.0;
|
||||
dutyref = saturation(sensorValue2 * (1.0 / 1023.0), 0.99, 0.33);
|
||||
}else{
|
||||
iL = current_mA / 1000.0;
|
||||
dutyref = sensorValue2 * (1.0 / 1023.0);
|
||||
}
|
||||
}
|
||||
|
||||
float saturation(float sat_input, float uplim, float lowlim){ // Saturation function
|
||||
if (sat_input > uplim)
|
||||
sat_input = uplim;
|
||||
else if (sat_input < lowlim)
|
||||
sat_input = lowlim;
|
||||
else
|
||||
;
|
||||
return sat_input;
|
||||
}
|
||||
|
||||
void pwm_modulate(float pwm_input){ // PWM function
|
||||
analogWrite(6, (int)(255 - pwm_input * 255));
|
||||
}
|
||||
|
||||
// This is a PID controller for the voltage
|
||||
|
||||
float pidv(float pid_input){
|
||||
float e_integration;
|
||||
e0v = pid_input;
|
||||
e_integration = e0v;
|
||||
|
||||
//anti-windup, if last-time pid output reaches the limitation, this time there won't be any intergrations.
|
||||
if (u1v >= uv_max){
|
||||
e_integration = 0;
|
||||
}else if (u1v <= uv_min){
|
||||
e_integration = 0;
|
||||
}
|
||||
|
||||
delta_uv = kpv * (e0v - e1v) + kiv * Ts * e_integration + kdv / Ts * (e0v - 2 * e1v + e2v); //incremental PID programming avoids integrations.there is another PID program called positional PID.
|
||||
u0v = u1v + delta_uv; //this time's control output
|
||||
|
||||
//output limitation
|
||||
saturation(u0v, uv_max, uv_min);
|
||||
|
||||
u1v = u0v; //update last time's control output
|
||||
e2v = e1v; //update last last time's error
|
||||
e1v = e0v; // update last time's error
|
||||
return u0v;
|
||||
}
|
||||
|
||||
// This is a PID controller for the current
|
||||
|
||||
float pidi(float pid_input){
|
||||
float e_integration;
|
||||
e0i = pid_input;
|
||||
e_integration = e0i;
|
||||
|
||||
//anti-windup
|
||||
if (u1i >= ui_max){
|
||||
e_integration = 0;
|
||||
}
|
||||
else if (u1i <= ui_min){
|
||||
e_integration = 0;
|
||||
}
|
||||
|
||||
delta_ui = kpi * (e0i - e1i) + kii * Ts * e_integration + kdi / Ts * (e0i - 2 * e1i + e2i); //incremental PID programming avoids integrations.
|
||||
u0i = u1i + delta_ui; //this time's control output
|
||||
|
||||
//output limitation
|
||||
saturation(u0i, ui_max, ui_min);
|
||||
|
||||
u1i = u0i; //update last time's control output
|
||||
e2i = e1i; //update last last time's error
|
||||
e1i = e0i; // update last time's error
|
||||
return u0i;
|
||||
}
|
||||
|
||||
// This is a P!ID contrller for motor speed
|
||||
|
||||
float pid_ms(int dist_to_move, int *dist_to_move_prev, unsigned long *time_pid_prev, float kps, float kds){
|
||||
|
||||
int T_diff = millis() - *time_pid_prev;
|
||||
float speed = (kps * dist_to_move) + ((kds/T_diff) * (dist_to_move - *dist_to_move_prev));
|
||||
*time_pid_prev = millis();
|
||||
|
||||
Serial.println(speed);
|
||||
|
||||
if (speed >= 1) speed = 1;
|
||||
else if (speed <= 0.5) speed = 0.5;
|
||||
|
||||
*dist_to_move_prev = dist_to_move;
|
||||
return speed;
|
||||
}
|
||||
|
||||
// This is a P!ID contrller for heading using optical flow
|
||||
|
||||
float pid_h_ms(bool left, float speed, int dist_to_move, int *dist_to_move_prev, unsigned long *time_pid_prev, float kps, float kds){
|
||||
|
||||
int T_diff = millis() - *time_pid_prev;
|
||||
float speed_aug;
|
||||
|
||||
if ((dist_to_move > 0 && !left )||( dist_to_move < 0 && left)){
|
||||
float speed_aug_mult = (kps * dist_to_move) + ((kds/T_diff) * (dist_to_move - *dist_to_move_prev));
|
||||
if (speed_aug_mult >= 2) speed_aug_mult = 2;
|
||||
else if (speed_aug_mult <= 1) speed_aug_mult = 1;
|
||||
speed_aug = speed / dist_to_move;
|
||||
}else{
|
||||
speed_aug = speed;
|
||||
}
|
||||
|
||||
*time_pid_prev = millis();
|
||||
|
||||
if (speed_aug >= 1) speed_aug = 1;
|
||||
else if (speed_aug <= 0.3) speed_aug = 0.3;
|
||||
|
||||
*dist_to_move_prev = dist_to_move;
|
||||
return speed_aug;
|
||||
}
|
11
Drive/test/README
Normal file
11
Drive/test/README
Normal file
|
@ -0,0 +1,11 @@
|
|||
|
||||
This directory is intended for PlatformIO Unit Testing and project tests.
|
||||
|
||||
Unit Testing is a software testing method by which individual units of
|
||||
source code, sets of one or more MCU program modules together with associated
|
||||
control data, usage procedures, and operating procedures, are tested to
|
||||
determine whether they are fit for use. Unit testing finds problems early
|
||||
in the development cycle.
|
||||
|
||||
More information about PlatformIO Unit Testing:
|
||||
- https://docs.platformio.org/page/plus/unit-testing.html
|
340
Energy/Balance+SOH estimation.ino
Normal file
340
Energy/Balance+SOH estimation.ino
Normal file
|
@ -0,0 +1,340 @@
|
|||
#include <Wire.h>
|
||||
#include <INA219_WE.h>
|
||||
#include <SPI.h>
|
||||
#include <SD.h>
|
||||
|
||||
INA219_WE ina219; // this is the instantiation of the library for the current sensor
|
||||
|
||||
// set up variables using the SD utility library functions:
|
||||
Sd2Card card;
|
||||
SdVolume volume;
|
||||
SdFile root;
|
||||
|
||||
const int chipSelect = 10;
|
||||
unsigned int rest_timer;
|
||||
unsigned int loop_trigger;
|
||||
unsigned int int_count = 0; // a variables to count the interrupts. Used for program debugging.
|
||||
float u0i, u1i, delta_ui, e0i, e1i, e2i; // Internal values for the current controller
|
||||
float ui_max = 1, ui_min = 0; //anti-windup limitation
|
||||
float kpi = 0.02512, kii = 39.4, kdi = 0; // current pid.
|
||||
float Ts = 0.001; //1 kHz control frequency.
|
||||
float current_measure, current_ref = 0, error_amps; // Current Control
|
||||
float pwm_out;
|
||||
float V_Bat;
|
||||
boolean input_switch;
|
||||
int state_num=0,next_state;
|
||||
String dataString;
|
||||
|
||||
|
||||
float cell_1_read = 0;
|
||||
float cell_2_read = 0;
|
||||
int balance_counter = 0;
|
||||
|
||||
float initial_V_lookup[] = {1} ;
|
||||
float initial_SOC_lookup[] = {1};
|
||||
float initial_SOC = 0;
|
||||
float coloumb_total = 0;
|
||||
float coloumb_change = 0;
|
||||
float current_SOC = 0;
|
||||
float battery_capacity = 1700000;
|
||||
int initial_SOC_counter = 1;
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
void setup() {
|
||||
//Some General Setup Stuff
|
||||
|
||||
Wire.begin(); // We need this for the i2c comms for the current sensor
|
||||
Wire.setClock(700000); // set the comms speed for i2c
|
||||
ina219.init(); // this initiates the current sensor
|
||||
Serial.begin(9600); // USB Communications
|
||||
|
||||
|
||||
//Check for the SD Card
|
||||
Serial.println("\nInitializing SD card...");
|
||||
if (!SD.begin(chipSelect)) {
|
||||
Serial.println("* is a card inserted?");
|
||||
while (true) {} //It will stick here FOREVER if no SD is in on boot
|
||||
} else {
|
||||
Serial.println("Wiring is correct and a card is present.");
|
||||
}
|
||||
|
||||
if (SD.exists("BatCycle.csv")) { // Wipe the datalog when starting
|
||||
SD.remove("BatCycle.csv");
|
||||
}
|
||||
|
||||
|
||||
noInterrupts(); //disable all interrupts
|
||||
analogReference(EXTERNAL); // We are using an external analogue reference for the ADC
|
||||
|
||||
//SMPS Pins
|
||||
pinMode(13, OUTPUT); // Using the LED on Pin D13 to indicate status
|
||||
pinMode(2, INPUT_PULLUP); // Pin 2 is the input from the CL/OL switch
|
||||
pinMode(6, OUTPUT); // This is the PWM Pin
|
||||
|
||||
//LEDs on pin 7 and 8
|
||||
pinMode(7, OUTPUT);
|
||||
pinMode(8, OUTPUT);
|
||||
|
||||
//Analogue input, the battery voltage (also port B voltage)
|
||||
pinMode(A0, INPUT);
|
||||
|
||||
/// Battery manage
|
||||
|
||||
pinMode(3, OUTPUT);
|
||||
pinMode(4, OUTPUT);
|
||||
pinMode(5, OUTPUT);
|
||||
pinMode(9, OUTPUT);
|
||||
pinMode(A1, INPUT);
|
||||
pinMode(A2, INPUT);
|
||||
|
||||
// TimerA0 initialization for 1kHz control-loop interrupt.
|
||||
TCA0.SINGLE.PER = 999; //
|
||||
TCA0.SINGLE.CMP1 = 999; //
|
||||
TCA0.SINGLE.CTRLA = TCA_SINGLE_CLKSEL_DIV16_gc | TCA_SINGLE_ENABLE_bm; //16 prescaler, 1M.
|
||||
TCA0.SINGLE.INTCTRL = TCA_SINGLE_CMP1_bm;
|
||||
|
||||
// TimerB0 initialization for PWM output
|
||||
TCB0.CTRLA = TCB_CLKSEL_CLKDIV1_gc | TCB_ENABLE_bm; //62.5kHz
|
||||
|
||||
interrupts(); //enable interrupts.
|
||||
analogWrite(6, 120); //just a default state to start with
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (loop_trigger == 1){ // FAST LOOP (1kHZ)
|
||||
state_num = next_state; //state transition
|
||||
V_Bat = analogRead(A0)*4.096/1.03; //check the battery voltage (1.03 is a correction for measurement error, you need to check this works for you)
|
||||
if ((V_Bat > 3700 || V_Bat < 2400)) { //Checking for Error states (just battery voltage for now)
|
||||
state_num = 5; //go directly to jail
|
||||
next_state = 5; // stay in jail
|
||||
digitalWrite(7,true); //turn on the red LED
|
||||
current_ref = 0; // no current
|
||||
}
|
||||
current_measure = (ina219.getCurrent_mA()); // sample the inductor current (via the sensor chip)
|
||||
error_amps = (current_ref - current_measure) / 1000; //PID error calculation
|
||||
pwm_out = pidi(error_amps); //Perform the PID controller calculation
|
||||
pwm_out = saturation(pwm_out, 0.99, 0.01); //duty_cycle saturation
|
||||
analogWrite(6, (int)(255 - pwm_out * 255)); // write it out (inverting for the Buck here)
|
||||
int_count++; //count how many interrupts since this was last reset to zero
|
||||
loop_trigger = 0; //reset the trigger and move on with life
|
||||
}
|
||||
|
||||
if (int_count == 1000) { // SLOW LOOP (1Hz)
|
||||
input_switch = digitalRead(2); //get the OL/CL switch status
|
||||
switch (state_num) { // STATE MACHINE (see diagram)
|
||||
case 0:{ // Start state (no current, no LEDs)
|
||||
current_ref = 0;
|
||||
if (input_switch == 1) { // if switch, move to charge
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
} else { // otherwise stay put
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 1:{ // Charge state (250mA and a green LED)
|
||||
current_ref = 250;
|
||||
|
||||
balance_counter = balance_counter + 1;
|
||||
if(balance_counter == 20){
|
||||
manage_battery();
|
||||
}
|
||||
|
||||
if( initial_SOC_counter == 1){
|
||||
initial_SOC = get_initial_SOC();
|
||||
initial_SOC_counter == 0;
|
||||
}
|
||||
|
||||
get_current_SOC();
|
||||
|
||||
|
||||
if (V_Bat < 3550) { // if not charged, stay put
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
} else { // otherwise go to charge rest
|
||||
next_state = 2;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
if(input_switch == 0){ // UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 2:{ // Charge Rest, green LED is off and no current
|
||||
current_ref = 0;
|
||||
if (rest_timer < 30) { // Stay here if timer < 30
|
||||
next_state = 2;
|
||||
digitalWrite(8,false);
|
||||
rest_timer++;
|
||||
} else { // Or move to discharge (and reset the timer)
|
||||
next_state = 3;
|
||||
digitalWrite(8,false);
|
||||
rest_timer = 0;
|
||||
}
|
||||
if(input_switch == 0){ // UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 3:{ //Discharge state (-250mA and no LEDs)
|
||||
current_ref = -250;
|
||||
|
||||
balance_counter = balance_counter + 1;
|
||||
if(balance_counter == 5){
|
||||
manage_battery();
|
||||
}
|
||||
|
||||
initial_SOC = get_initial_SOC();
|
||||
get_current_SOC();
|
||||
|
||||
|
||||
|
||||
if (V_Bat > 2500) { // While not at minimum volts, stay here
|
||||
next_state = 3;
|
||||
digitalWrite(8,false);
|
||||
} else { // If we reach full discharged, move to rest
|
||||
next_state = 4;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 4:{ // Discharge rest, no LEDs no current
|
||||
current_ref = 0;
|
||||
if (rest_timer < 30) { // Rest here for 30s like before
|
||||
next_state = 4;
|
||||
digitalWrite(8,false);
|
||||
rest_timer++;
|
||||
} else { // When thats done, move back to charging (and light the green LED)
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
rest_timer = 0;
|
||||
}
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 5: { // ERROR state RED led and no current
|
||||
current_ref = 0;
|
||||
next_state = 5; // Always stay here
|
||||
digitalWrite(7,true);
|
||||
digitalWrite(8,false);
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(7,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
default :{ // Should not end up here ....
|
||||
Serial.println("Boop");
|
||||
current_ref = 0;
|
||||
next_state = 5; // So if we are here, we go to error
|
||||
digitalWrite(7,true);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
dataString = String(state_num) + "," + String(V_Bat) + "," + String(balance_counter) + "," + String(cell_1_read) + "," + String(cell_2_read) + "," + String(current_ref) + "," + String(current_measure) + "," + String(initial_SOC) + "," + String( current_SOC) ; //build a datastring for the CSV file
|
||||
Serial.println(dataString); // send it to serial as well in case a computer is connected
|
||||
File dataFile = SD.open("BatCycle.csv", FILE_WRITE); // open our CSV file
|
||||
if (dataFile){ //If we succeeded (usually this fails if the SD card is out)
|
||||
dataFile.println(dataString); // print the data
|
||||
} else {
|
||||
Serial.println("File not open"); //otherwise print an error
|
||||
}
|
||||
dataFile.close(); // close the file
|
||||
int_count = 0; // reset the interrupt count so we dont come back here for 1000ms
|
||||
}
|
||||
}
|
||||
|
||||
// Timer A CMP1 interrupt. Every 1000us the program enters this interrupt. This is the fast 1kHz loop
|
||||
ISR(TCA0_CMP1_vect) {
|
||||
loop_trigger = 1; //trigger the loop when we are back in normal flow
|
||||
TCA0.SINGLE.INTFLAGS |= TCA_SINGLE_CMP1_bm; //clear interrupt flag
|
||||
}
|
||||
|
||||
float saturation( float sat_input, float uplim, float lowlim) { // Saturation function
|
||||
if (sat_input > uplim) sat_input = uplim;
|
||||
else if (sat_input < lowlim ) sat_input = lowlim;
|
||||
else;
|
||||
return sat_input;
|
||||
}
|
||||
|
||||
float pidi(float pid_input) { // discrete PID function
|
||||
float e_integration;
|
||||
e0i = pid_input;
|
||||
e_integration = e0i;
|
||||
|
||||
//anti-windup
|
||||
if (u1i >= ui_max) {
|
||||
e_integration = 0;
|
||||
} else if (u1i <= ui_min) {
|
||||
e_integration = 0;
|
||||
}
|
||||
|
||||
delta_ui = kpi * (e0i - e1i) + kii * Ts * e_integration + kdi / Ts * (e0i - 2 * e1i + e2i); //incremental PID programming avoids integrations.
|
||||
u0i = u1i + delta_ui; //this time's control output
|
||||
|
||||
//output limitation
|
||||
saturation(u0i, ui_max, ui_min);
|
||||
|
||||
u1i = u0i; //update last time's control output
|
||||
e2i = e1i; //update last last time's error
|
||||
e1i = e0i; // update last time's error
|
||||
return u0i;
|
||||
}
|
||||
|
||||
|
||||
void manage_battery(){
|
||||
|
||||
// First battery
|
||||
//measure first battery and balance if needed ( relay = D4 , discharge = D5, Measure= A1)
|
||||
digitalWrite(4, HIGH);
|
||||
cell_1_read = analogRead(A1)*4.096/1.03;;
|
||||
digitalWrite(4, LOW);
|
||||
if( cell_1_read > 3600){
|
||||
digitalWrite(5, HIGH);
|
||||
}
|
||||
if(cell_1_read < 2500){
|
||||
next_state = 1;
|
||||
}
|
||||
//second battery
|
||||
//measure second battery and balance if needed ( relay = D3 , discharge = D9, Measure= A2)
|
||||
digitalWrite(3, HIGH);
|
||||
cell_2_read = analogRead(A2)*4.096/1.03;
|
||||
digitalWrite(3,LOW);
|
||||
if( cell_2_read > 3600){
|
||||
digitalWrite(9, HIGH);
|
||||
}
|
||||
if( cell_2_read < 2500){
|
||||
next_state = 1;
|
||||
}
|
||||
// reset counter
|
||||
balance_counter = 0;
|
||||
}
|
||||
|
||||
|
||||
float get_initial_SOC(){
|
||||
float initial = 0.3;
|
||||
return initial;
|
||||
}
|
||||
|
||||
void get_current_SOC(){
|
||||
coloumb_total = coloumb_total + abs(current_measure);
|
||||
coloumb_change = coloumb_change + current_measure;
|
||||
|
||||
current_SOC = initial_SOC + ((coloumb_change)/(battery_capacity));
|
||||
}
|
246
Energy/Battery Characterisation.ino
Normal file
246
Energy/Battery Characterisation.ino
Normal file
|
@ -0,0 +1,246 @@
|
|||
#include <Wire.h>
|
||||
#include <INA219_WE.h>
|
||||
#include <SPI.h>
|
||||
#include <SD.h>
|
||||
|
||||
INA219_WE ina219; // this is the instantiation of the library for the current sensor
|
||||
|
||||
// set up variables using the SD utility library functions:
|
||||
Sd2Card card;
|
||||
SdVolume volume;
|
||||
SdFile root;
|
||||
|
||||
const int chipSelect = 10;
|
||||
unsigned int rest_timer;
|
||||
unsigned int loop_trigger;
|
||||
unsigned int int_count = 0; // a variables to count the interrupts. Used for program debugging.
|
||||
float u0i, u1i, delta_ui, e0i, e1i, e2i; // Internal values for the current controller
|
||||
float ui_max = 1, ui_min = 0; //anti-windup limitation
|
||||
float kpi = 0.02512, kii = 39.4, kdi = 0; // current pid.
|
||||
float Ts = 0.001; //1 kHz control frequency.
|
||||
float current_measure, current_ref = 0, error_amps; // Current Control
|
||||
float pwm_out;
|
||||
float V_Bat;
|
||||
boolean input_switch;
|
||||
int state_num=0,next_state;
|
||||
String dataString;
|
||||
|
||||
void setup() {
|
||||
//Some General Setup Stuff
|
||||
|
||||
Wire.begin(); // We need this for the i2c comms for the current sensor
|
||||
Wire.setClock(700000); // set the comms speed for i2c
|
||||
ina219.init(); // this initiates the current sensor
|
||||
Serial.begin(9600); // USB Communications
|
||||
|
||||
|
||||
//Check for the SD Card
|
||||
Serial.println("\nInitializing SD card...");
|
||||
if (!SD.begin(chipSelect)) {
|
||||
Serial.println("* is a card inserted?");
|
||||
while (true) {} //It will stick here FOREVER if no SD is in on boot
|
||||
} else {
|
||||
Serial.println("Wiring is correct and a card is present.");
|
||||
}
|
||||
|
||||
if (SD.exists("BatCycle.csv")) { // Wipe the datalog when starting
|
||||
SD.remove("BatCycle.csv");
|
||||
}
|
||||
|
||||
|
||||
noInterrupts(); //disable all interrupts
|
||||
analogReference(EXTERNAL); // We are using an external analogue reference for the ADC
|
||||
|
||||
//SMPS Pins
|
||||
pinMode(13, OUTPUT); // Using the LED on Pin D13 to indicate status
|
||||
pinMode(2, INPUT_PULLUP); // Pin 2 is the input from the CL/OL switch
|
||||
pinMode(6, OUTPUT); // This is the PWM Pin
|
||||
|
||||
//LEDs on pin 7 and 8
|
||||
pinMode(7, OUTPUT);
|
||||
pinMode(8, OUTPUT);
|
||||
|
||||
//Analogue input, the battery voltage (also port B voltage)
|
||||
pinMode(A0, INPUT);
|
||||
|
||||
// TimerA0 initialization for 1kHz control-loop interrupt.
|
||||
TCA0.SINGLE.PER = 999; //
|
||||
TCA0.SINGLE.CMP1 = 999; //
|
||||
TCA0.SINGLE.CTRLA = TCA_SINGLE_CLKSEL_DIV16_gc | TCA_SINGLE_ENABLE_bm; //16 prescaler, 1M.
|
||||
TCA0.SINGLE.INTCTRL = TCA_SINGLE_CMP1_bm;
|
||||
|
||||
// TimerB0 initialization for PWM output
|
||||
TCB0.CTRLA = TCB_CLKSEL_CLKDIV1_gc | TCB_ENABLE_bm; //62.5kHz
|
||||
|
||||
interrupts(); //enable interrupts.
|
||||
analogWrite(6, 120); //just a default state to start with
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (loop_trigger == 1){ // FAST LOOP (1kHZ)
|
||||
state_num = next_state; //state transition
|
||||
V_Bat = analogRead(A0)*4.096/1.03; //check the battery voltage (1.03 is a correction for measurement error, you need to check this works for you)
|
||||
if ((V_Bat > 3700 || V_Bat < 2400)) { //Checking for Error states (just battery voltage for now)
|
||||
state_num = 5; //go directly to jail
|
||||
next_state = 5; // stay in jail
|
||||
digitalWrite(7,true); //turn on the red LED
|
||||
current_ref = 0; // no current
|
||||
}
|
||||
current_measure = (ina219.getCurrent_mA()); // sample the inductor current (via the sensor chip)
|
||||
error_amps = (current_ref - current_measure) / 1000; //PID error calculation
|
||||
pwm_out = pidi(error_amps); //Perform the PID controller calculation
|
||||
pwm_out = saturation(pwm_out, 0.99, 0.01); //duty_cycle saturation
|
||||
analogWrite(6, (int)(255 - pwm_out * 255)); // write it out (inverting for the Buck here)
|
||||
int_count++; //count how many interrupts since this was last reset to zero
|
||||
loop_trigger = 0; //reset the trigger and move on with life
|
||||
}
|
||||
|
||||
if (int_count == 1000) { // SLOW LOOP (1Hz)
|
||||
input_switch = digitalRead(2); //get the OL/CL switch status
|
||||
switch (state_num) { // STATE MACHINE (see diagram)
|
||||
case 0:{ // Start state (no current, no LEDs)
|
||||
current_ref = 0;
|
||||
if (input_switch == 1) { // if switch, move to charge
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
} else { // otherwise stay put
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 1:{ // Charge state (250mA and a green LED)
|
||||
current_ref = 400;
|
||||
if (V_Bat < 3600) { // if not charged, stay put
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
} else { // otherwise go to charge rest
|
||||
next_state = 2;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
if(input_switch == 0){ // UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 2:{ // Charge Rest, green LED is off and no current
|
||||
current_ref = 0;
|
||||
if (rest_timer < 30) { // Stay here if timer < 30
|
||||
next_state = 2;
|
||||
digitalWrite(8,false);
|
||||
rest_timer++;
|
||||
} else { // Or move to discharge (and reset the timer)
|
||||
next_state = 3;
|
||||
digitalWrite(8,false);
|
||||
rest_timer = 0;
|
||||
}
|
||||
if(input_switch == 0){ // UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 3:{ //Discharge state (-250mA and no LEDs)
|
||||
current_ref = -400;
|
||||
if (V_Bat > 2500) { // While not at minimum volts, stay here
|
||||
next_state = 3;
|
||||
digitalWrite(8,false);
|
||||
} else { // If we reach full discharged, move to rest
|
||||
next_state = 4;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 4:{ // Discharge rest, no LEDs no current
|
||||
current_ref = 0;
|
||||
if (rest_timer < 30) { // Rest here for 30s like before
|
||||
next_state = 4;
|
||||
digitalWrite(8,false);
|
||||
rest_timer++;
|
||||
} else { // When thats done, move back to charging (and light the green LED)
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
rest_timer = 0;
|
||||
}
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 5: { // ERROR state RED led and no current
|
||||
current_ref = 0;
|
||||
next_state = 5; // Always stay here
|
||||
digitalWrite(7,true);
|
||||
digitalWrite(8,false);
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(7,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
default :{ // Should not end up here ....
|
||||
Serial.println("Boop");
|
||||
current_ref = 0;
|
||||
next_state = 5; // So if we are here, we go to error
|
||||
digitalWrite(7,true);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
dataString = String(state_num) + "," + String(V_Bat) + "," + String(current_ref) + "," + String(current_measure); //build a datastring for the CSV file
|
||||
Serial.println(dataString); // send it to serial as well in case a computer is connected
|
||||
File dataFile = SD.open("BatCycle.csv", FILE_WRITE); // open our CSV file
|
||||
if (dataFile){ //If we succeeded (usually this fails if the SD card is out)
|
||||
dataFile.println(dataString); // print the data
|
||||
} else {
|
||||
Serial.println("File not open"); //otherwise print an error
|
||||
}
|
||||
dataFile.close(); // close the file
|
||||
int_count = 0; // reset the interrupt count so we dont come back here for 1000ms
|
||||
}
|
||||
}
|
||||
|
||||
// Timer A CMP1 interrupt. Every 1000us the program enters this interrupt. This is the fast 1kHz loop
|
||||
ISR(TCA0_CMP1_vect) {
|
||||
loop_trigger = 1; //trigger the loop when we are back in normal flow
|
||||
TCA0.SINGLE.INTFLAGS |= TCA_SINGLE_CMP1_bm; //clear interrupt flag
|
||||
}
|
||||
|
||||
float saturation( float sat_input, float uplim, float lowlim) { // Saturation function
|
||||
if (sat_input > uplim) sat_input = uplim;
|
||||
else if (sat_input < lowlim ) sat_input = lowlim;
|
||||
else;
|
||||
return sat_input;
|
||||
}
|
||||
|
||||
float pidi(float pid_input) { // discrete PID function
|
||||
float e_integration;
|
||||
e0i = pid_input;
|
||||
e_integration = e0i;
|
||||
|
||||
//anti-windup
|
||||
if (u1i >= ui_max) {
|
||||
e_integration = 0;
|
||||
} else if (u1i <= ui_min) {
|
||||
e_integration = 0;
|
||||
}
|
||||
|
||||
delta_ui = kpi * (e0i - e1i) + kii * Ts * e_integration + kdi / Ts * (e0i - 2 * e1i + e2i); //incremental PID programming avoids integrations.
|
||||
u0i = u1i + delta_ui; //this time's control output
|
||||
|
||||
//output limitation
|
||||
saturation(u0i, ui_max, ui_min);
|
||||
|
||||
u1i = u0i; //update last time's control output
|
||||
e2i = e1i; //update last last time's error
|
||||
e1i = e0i; // update last time's error
|
||||
return u0i;
|
||||
}
|
199
Energy/PV Analyses.ino
Normal file
199
Energy/PV Analyses.ino
Normal file
|
@ -0,0 +1,199 @@
|
|||
#include <Wire.h>
|
||||
#include <INA219_WE.h>
|
||||
#include <SPI.h>
|
||||
#include <SD.h>
|
||||
|
||||
INA219_WE ina219; // this is the instantiation of the library for the current sensor
|
||||
|
||||
// set up variables using the SD utility library functions:
|
||||
Sd2Card card;
|
||||
SdVolume volume;
|
||||
SdFile root;
|
||||
|
||||
const int chipSelect = 10;
|
||||
unsigned int rest_timer;
|
||||
unsigned int loop_trigger;
|
||||
unsigned int int_count = 0; // a variables to count the interrupts. Used for program debugging.
|
||||
float u0i, u1i, delta_ui, e0i, e1i, e2i; // Internal values for the current controller
|
||||
float ui_max = 1, ui_min = 0; //anti-windup limitation
|
||||
float kpi = 0.02512, kii = 39.4, kdi = 0; // current pid.
|
||||
float Ts = 0.001; //1 kHz control frequency.
|
||||
float current_measure, current_ref = 0, error_amps; // Current Control
|
||||
float pwm_out;
|
||||
float V_Bat;
|
||||
boolean input_switch;
|
||||
int state_num=0,next_state;
|
||||
String dataString;
|
||||
int PWM_in = 1;
|
||||
float duty_cycle = 0;
|
||||
int counter = 5;
|
||||
|
||||
void setup() {
|
||||
//Some General Setup Stuff
|
||||
|
||||
Wire.begin(); // We need this for the i2c comms for the current sensor
|
||||
Wire.setClock(700000); // set the comms speed for i2c
|
||||
ina219.init(); // this initiates the current sensor
|
||||
Serial.begin(9600); // USB Communications
|
||||
|
||||
|
||||
//Check for the SD Card
|
||||
Serial.println("\nInitializing SD card...");
|
||||
if (!SD.begin(chipSelect)) {
|
||||
Serial.println("* is a card inserted?");
|
||||
while (true) {} //It will stick here FOREVER if no SD is in on boot
|
||||
} else {
|
||||
Serial.println("Wiring is correct and a card is present.");
|
||||
}
|
||||
|
||||
if (SD.exists("BatCycle.csv")) { // Wipe the datalog when starting
|
||||
SD.remove("BatCycle.csv");
|
||||
}
|
||||
|
||||
|
||||
noInterrupts(); //disable all interrupts
|
||||
analogReference(EXTERNAL); // We are using an external analogue reference for the ADC
|
||||
|
||||
//SMPS Pins
|
||||
pinMode(13, OUTPUT); // Using the LED on Pin D13 to indicate status
|
||||
pinMode(2, INPUT_PULLUP); // Pin 2 is the input from the CL/OL switch
|
||||
pinMode(6, OUTPUT); // This is the PWM Pin
|
||||
|
||||
//LEDs on pin 7 and 8
|
||||
pinMode(7, OUTPUT);
|
||||
pinMode(8, OUTPUT);
|
||||
|
||||
//Analogue input, the battery voltage (also port B voltage)
|
||||
pinMode(A0, INPUT);
|
||||
|
||||
// TimerA0 initialization for 1kHz control-loop interrupt.
|
||||
TCA0.SINGLE.PER = 999; //
|
||||
TCA0.SINGLE.CMP1 = 999; //
|
||||
TCA0.SINGLE.CTRLA = TCA_SINGLE_CLKSEL_DIV16_gc | TCA_SINGLE_ENABLE_bm; //16 prescaler, 1M.
|
||||
TCA0.SINGLE.INTCTRL = TCA_SINGLE_CMP1_bm;
|
||||
|
||||
// TimerB0 initialization for PWM output
|
||||
TCB0.CTRLA = TCB_CLKSEL_CLKDIV1_gc | TCB_ENABLE_bm; //62.5kHz
|
||||
|
||||
interrupts(); //enable interrupts.
|
||||
analogWrite(6, 120); //just a default state to start with
|
||||
|
||||
}
|
||||
|
||||
void loop() {
|
||||
if (loop_trigger == 1){ // FAST LOOP (1kHZ)
|
||||
state_num = next_state; //state transition
|
||||
V_Bat = analogRead(A0)*4.096/1.03; //check the battery voltage (1.03 is a correction for measurement error, you need to check this works for you)
|
||||
current_measure = (ina219.getCurrent_mA()); // sample the inductor current (via the sensor chip)
|
||||
int_count++; //count how many interrupts since this was last reset to zero
|
||||
loop_trigger = 0; //reset the trigger and move on with life
|
||||
}
|
||||
|
||||
if (int_count == 1000) { // SLOW LOOP (1Hz)
|
||||
input_switch = digitalRead(2); //get the OL/CL switch status
|
||||
switch (state_num) { // STATE MACHINE (see diagram)
|
||||
|
||||
case 0:{ // Start state (no current, no LEDs)
|
||||
current_ref = 0;
|
||||
if (input_switch == 1) { // if switch, move to charge
|
||||
next_state = 1;
|
||||
digitalWrite(8,true);
|
||||
} else { // otherwise stay put
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
case 1:{ // Charge state (250mA and a green LED)
|
||||
analogWrite(6,PWM_in);
|
||||
|
||||
if(counter == 5){
|
||||
if(PWM_in < 255) {
|
||||
PWM_in = PWM_in + 1;
|
||||
}
|
||||
else {
|
||||
PWM_in = 1;
|
||||
}
|
||||
counter = 0;
|
||||
}
|
||||
|
||||
counter = counter +1;
|
||||
duty_cycle = (PWM_in /255)*100;
|
||||
|
||||
if(input_switch == 0){ // UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(8,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
case 5: { // ERROR state RED led and no current
|
||||
current_ref = 0;
|
||||
next_state = 5; // Always stay here
|
||||
digitalWrite(7,true);
|
||||
digitalWrite(8,false);
|
||||
if(input_switch == 0){ //UNLESS the switch = 0, then go back to start
|
||||
next_state = 0;
|
||||
digitalWrite(7,false);
|
||||
}
|
||||
break;
|
||||
}
|
||||
|
||||
default :{ // Should not end up here ....
|
||||
Serial.println("Boop");
|
||||
current_ref = 0;
|
||||
next_state = 5; // So if we are here, we go to error
|
||||
digitalWrite(7,true);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
dataString = String(state_num) + "," + String(V_Bat) + "," + String(current_measure) + "," + String(PWM_in) + "," + String(duty_cycle); ; //build a datastring for the CSV file
|
||||
Serial.println(dataString); // send it to serial as well in case a computer is connected
|
||||
File dataFile = SD.open("BatCycle.csv", FILE_WRITE); // open our CSV file
|
||||
if (dataFile){ //If we succeeded (usually this fails if the SD card is out)
|
||||
dataFile.println(dataString); // print the data
|
||||
} else {
|
||||
Serial.println("File not open"); //otherwise print an error
|
||||
}
|
||||
dataFile.close(); // close the file
|
||||
int_count = 0; // reset the interrupt count so we dont come back here for 1000ms
|
||||
}
|
||||
}
|
||||
|
||||
// Timer A CMP1 interrupt. Every 1000us the program enters this interrupt. This is the fast 1kHz loop
|
||||
ISR(TCA0_CMP1_vect) {
|
||||
loop_trigger = 1; //trigger the loop when we are back in normal flow
|
||||
TCA0.SINGLE.INTFLAGS |= TCA_SINGLE_CMP1_bm; //clear interrupt flag
|
||||
}
|
||||
|
||||
float saturation( float sat_input, float uplim, float lowlim) { // Saturation function
|
||||
if (sat_input > uplim) sat_input = uplim;
|
||||
else if (sat_input < lowlim ) sat_input = lowlim;
|
||||
else;
|
||||
return sat_input;
|
||||
}
|
||||
|
||||
float pidi(float pid_input) { // discrete PID function
|
||||
float e_integration;
|
||||
e0i = pid_input;
|
||||
e_integration = e0i;
|
||||
|
||||
//anti-windup
|
||||
if (u1i >= ui_max) {
|
||||
e_integration = 0;
|
||||
} else if (u1i <= ui_min) {
|
||||
e_integration = 0;
|
||||
}
|
||||
|
||||
delta_ui = kpi * (e0i - e1i) + kii * Ts * e_integration + kdi / Ts * (e0i - 2 * e1i + e2i); //incremental PID programming avoids integrations.
|
||||
u0i = u1i + delta_ui; //this time's control output
|
||||
|
||||
//output limitation
|
||||
saturation(u0i, ui_max, ui_min);
|
||||
|
||||
u1i = u0i; //update last time's control output
|
||||
e2i = e1i; //update last last time's error
|
||||
e1i = e0i; // update last time's error
|
||||
return u0i;
|
||||
}
|
|
@ -781,7 +781,7 @@
|
|||
<delegate id="delegate_CommonDockStationFactory">
|
||||
<root>true</root>
|
||||
<content delegate="flap dock">
|
||||
<window auto="true" direction="NORTH"/>
|
||||
<window auto="true" direction="SOUTH"/>
|
||||
<placeholders>
|
||||
<version>0</version>
|
||||
<format>dock.PlaceholderList</format>
|
||||
|
@ -827,7 +827,7 @@
|
|||
<fullscreen-action>false</fullscreen-action>
|
||||
<node nodeId="1372710005721" orientation="HORIZONTAL" divider="0.22181146025878004">
|
||||
<node nodeId="1375985011088" orientation="VERTICAL" divider="0.504054054054054">
|
||||
<leaf id="2" nodeId="1375985003630">
|
||||
<leaf id="1" nodeId="1375985003630">
|
||||
<placeholders>
|
||||
<placeholder>dock.single.Clock\ Domains\ \-\ Beta</placeholder>
|
||||
<placeholder>dock.single.IP\ Catalog</placeholder>
|
||||
|
@ -853,7 +853,7 @@
|
|||
</entry>
|
||||
</placeholder-map>
|
||||
</leaf>
|
||||
<leaf id="1" nodeId="1375985011087">
|
||||
<leaf id="0" nodeId="1375985011087">
|
||||
<placeholders>
|
||||
<placeholder>dock.single.Hierarchy</placeholder>
|
||||
</placeholders>
|
||||
|
@ -878,9 +878,9 @@
|
|||
</leaf>
|
||||
</node>
|
||||
<node nodeId="1372710005725" orientation="VERTICAL" divider="0.8051001821493625">
|
||||
<node nodeId="1372710005727" orientation="HORIZONTAL" divider="0.8413566475001963">
|
||||
<node nodeId="1372710005727" orientation="HORIZONTAL" divider="0.7178845934919044">
|
||||
<node nodeId="1372710005733" orientation="VERTICAL" divider="0.75">
|
||||
<leaf id="3" nodeId="1372710005735">
|
||||
<leaf id="2" nodeId="1372710005735">
|
||||
<placeholders>
|
||||
<placeholder>dock.single.Connections</placeholder>
|
||||
<placeholder>dock.single.System\ Contents</placeholder>
|
||||
|
@ -897,12 +897,18 @@
|
|||
<placeholder>dock.single.Interconnect\ Requirements</placeholder>
|
||||
<placeholder>dock.single.Instrumentation</placeholder>
|
||||
<placeholder>dock.single.Instance\ Parameters</placeholder>
|
||||
<placeholder>dock.single.Address\ Map</placeholder>
|
||||
<placeholder>dock.single.Domains</placeholder>
|
||||
</placeholders>
|
||||
<placeholder-map>
|
||||
<version>0</version>
|
||||
<format>dock.PlaceholderList</format>
|
||||
<entry>
|
||||
<key shared="false">
|
||||
<placeholder>dock.single.System\ Contents</placeholder>
|
||||
</key>
|
||||
<item key="convert" type="b">true</item>
|
||||
<item key="convert-keys" type="a"/>
|
||||
</entry>
|
||||
<entry>
|
||||
<key shared="false">
|
||||
<placeholder>dock.single.Address\ Map</placeholder>
|
||||
|
@ -965,7 +971,7 @@
|
|||
</leaf>
|
||||
</node>
|
||||
</node>
|
||||
<leaf id="0" nodeId="1372710005745">
|
||||
<leaf id="3" nodeId="1372710005745">
|
||||
<placeholders>
|
||||
<placeholder>dock.single.Messages</placeholder>
|
||||
<placeholder>dock.single.Generation\ Messages</placeholder>
|
||||
|
@ -996,16 +1002,6 @@
|
|||
</layout>
|
||||
</adjacent>
|
||||
<children ignore="false">
|
||||
<child>
|
||||
<layout factory="predefined" placeholder="dock.single.Messages">
|
||||
<replacement id="dockablesingle Messages"/>
|
||||
<delegate id="delegate_ccontrol backup factory id">
|
||||
<id>Messages</id>
|
||||
<area/>
|
||||
</delegate>
|
||||
</layout>
|
||||
<children ignore="false"/>
|
||||
</child>
|
||||
<child>
|
||||
<layout factory="delegate_StackDockStationFactory">
|
||||
<selected>0</selected>
|
||||
|
@ -1183,6 +1179,16 @@
|
|||
</child>
|
||||
</children>
|
||||
</child>
|
||||
<child>
|
||||
<layout factory="predefined" placeholder="dock.single.Messages">
|
||||
<replacement id="dockablesingle Messages"/>
|
||||
<delegate id="delegate_ccontrol backup factory id">
|
||||
<id>Messages</id>
|
||||
<area/>
|
||||
</delegate>
|
||||
</layout>
|
||||
<children ignore="false"/>
|
||||
</child>
|
||||
<child>
|
||||
<layout factory="predefined" placeholder="dock.single.Parameters">
|
||||
<replacement id="dockablesingle Parameters"/>
|
||||
|
@ -1611,21 +1617,9 @@
|
|||
</entry>
|
||||
<entry id="single Address Map" current="dock.mode.normal">
|
||||
<history>
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<mode>dock.mode.normal</mode>
|
||||
</history>
|
||||
<properties>
|
||||
<property id="dock.mode.maximized">
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<root>ccontrol center</root>
|
||||
<location>
|
||||
<property factory="SplitDockFullScreenPropertyFactory"/>
|
||||
<property factory="StackDockPropertyFactory">
|
||||
<index>1</index>
|
||||
<placeholder>dock.single.Address\ Map</placeholder>
|
||||
</property>
|
||||
</location>
|
||||
</property>
|
||||
<property id="dock.mode.normal">
|
||||
<mode>dock.mode.normal</mode>
|
||||
<root>ccontrol center</root>
|
||||
|
@ -1633,9 +1627,10 @@
|
|||
<property factory="SplitDockPlaceholderProperty">
|
||||
<placeholder>dock.single.Address\ Map</placeholder>
|
||||
<backup-path>
|
||||
<node location="RIGHT" size="0.7781885397412199" id="1372710005721"/>
|
||||
<node location="TOP" size="0.8051001821493625" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.8413566475001963" id="1372710005727"/>
|
||||
<node location="RIGHT" size="0.8" id="1372710005721"/>
|
||||
<node location="TOP" size="0.75" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.75" id="1372710005727"/>
|
||||
<node location="RIGHT" size="0.6666666666666667" id="1372710005729"/>
|
||||
<node location="TOP" size="0.75" id="1372710005733"/>
|
||||
<leaf id="1372710005735"/>
|
||||
</backup-path>
|
||||
|
@ -1852,21 +1847,9 @@
|
|||
</entry>
|
||||
<entry id="single System Contents" current="dock.mode.normal">
|
||||
<history>
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<mode>dock.mode.normal</mode>
|
||||
</history>
|
||||
<properties>
|
||||
<property id="dock.mode.maximized">
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<root>ccontrol center</root>
|
||||
<location>
|
||||
<property factory="SplitDockFullScreenPropertyFactory"/>
|
||||
<property factory="StackDockPropertyFactory">
|
||||
<index>0</index>
|
||||
<placeholder>dock.single.System\ Contents</placeholder>
|
||||
</property>
|
||||
</location>
|
||||
</property>
|
||||
<property id="dock.mode.normal">
|
||||
<mode>dock.mode.normal</mode>
|
||||
<root>ccontrol center</root>
|
||||
|
@ -1874,9 +1857,10 @@
|
|||
<property factory="SplitDockPlaceholderProperty">
|
||||
<placeholder>dock.single.System\ Contents</placeholder>
|
||||
<backup-path>
|
||||
<node location="RIGHT" size="0.7781885397412199" id="1372710005721"/>
|
||||
<node location="TOP" size="0.8051001821493625" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.8413566475001963" id="1372710005727"/>
|
||||
<node location="RIGHT" size="0.8" id="1372710005721"/>
|
||||
<node location="TOP" size="0.75" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.75" id="1372710005727"/>
|
||||
<node location="RIGHT" size="0.6666666666666667" id="1372710005729"/>
|
||||
<node location="TOP" size="0.75" id="1372710005733"/>
|
||||
<leaf id="1372710005735"/>
|
||||
</backup-path>
|
||||
|
@ -1892,21 +1876,9 @@
|
|||
<entry id="single Interconnect Requirements" current="dock.mode.normal">
|
||||
<history>
|
||||
<mode>dock.mode.minimized</mode>
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<mode>dock.mode.normal</mode>
|
||||
</history>
|
||||
<properties>
|
||||
<property id="dock.mode.maximized">
|
||||
<mode>dock.mode.maximized</mode>
|
||||
<root>ccontrol center</root>
|
||||
<location>
|
||||
<property factory="SplitDockFullScreenPropertyFactory"/>
|
||||
<property factory="StackDockPropertyFactory">
|
||||
<index>2</index>
|
||||
<placeholder>dock.single.Interconnect\ Requirements</placeholder>
|
||||
</property>
|
||||
</location>
|
||||
</property>
|
||||
<property id="dock.mode.minimized">
|
||||
<mode>dock.mode.minimized</mode>
|
||||
<root>ccontrol north</root>
|
||||
|
@ -1927,8 +1899,8 @@
|
|||
<placeholder>dock.single.Interconnect\ Requirements</placeholder>
|
||||
<backup-path>
|
||||
<node location="RIGHT" size="0.7781885397412199" id="1372710005721"/>
|
||||
<node location="TOP" size="0.8051001821493625" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.8413566475001963" id="1372710005727"/>
|
||||
<node location="TOP" size="0.75" id="1372710005725"/>
|
||||
<node location="LEFT" size="0.6183193900785428" id="1372710005727"/>
|
||||
<node location="TOP" size="0.75" id="1372710005733"/>
|
||||
<leaf id="1372710005735"/>
|
||||
</backup-path>
|
||||
|
@ -2168,7 +2140,24 @@
|
|||
</entry>
|
||||
</dockables>
|
||||
<modes>
|
||||
<entry id="dock.mode.maximized"/>
|
||||
<entry id="dock.mode.maximized">
|
||||
<maximized>
|
||||
<item id="ccontrol center">
|
||||
<mode>dock.mode.normal</mode>
|
||||
<location>
|
||||
<mode>dock.mode.normal</mode>
|
||||
<root>ccontrol center</root>
|
||||
<location>
|
||||
<property factory="SplitDockPathProperty">
|
||||
<node location="LEFT" size="0.22181146025878004" id="1372710005721"/>
|
||||
<node location="TOP" size="0.504054054054054" id="1375985011088"/>
|
||||
<leaf id="1375985003630"/>
|
||||
</property>
|
||||
</location>
|
||||
</location>
|
||||
</item>
|
||||
</maximized>
|
||||
</entry>
|
||||
</modes>
|
||||
</modes>
|
||||
</current>
|
||||
|
|
|
@ -15,45 +15,45 @@ preplace inst Qsys.TERASIC_CAMERA_0 -pg 1 -lvl 4 -y 740
|
|||
preplace inst Qsys.mipi_reset_n -pg 1 -lvl 8 -y 1190
|
||||
preplace inst Qsys.alt_vip_vfb_0 -pg 1 -lvl 5 -y 620
|
||||
preplace inst Qsys -pg 1 -lvl 1 -y 40 -regy -20
|
||||
preplace inst Qsys.uart_interface_0 -pg 1 -lvl 2 -y 330
|
||||
preplace inst Qsys.EEE_IMGPROC_0 -pg 1 -lvl 7 -y 600
|
||||
preplace inst Qsys.EEE_IMGPROC_0 -pg 1 -lvl 7 -y 700
|
||||
preplace inst Qsys.timer -pg 1 -lvl 8 -y 440
|
||||
preplace inst Qsys.mipi_pwdn_n -pg 1 -lvl 8 -y 1090
|
||||
preplace inst Qsys.key -pg 1 -lvl 8 -y 620
|
||||
preplace inst Qsys.uart_0 -pg 1 -lvl 3 -y 720
|
||||
preplace inst Qsys.sw -pg 1 -lvl 8 -y 1290
|
||||
preplace inst Qsys.TERASIC_AUTO_FOCUS_0 -pg 1 -lvl 6 -y 560
|
||||
preplace inst Qsys.nios2_gen2.cpu -pg 1
|
||||
preplace inst Qsys.nios2_gen2 -pg 1 -lvl 2 -y 520
|
||||
preplace inst Qsys.nios2_gen2 -pg 1 -lvl 2 -y 550
|
||||
preplace inst Qsys.i2c_opencores_mipi -pg 1 -lvl 8 -y 170
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)altpll_0.c1,(MASTER)Qsys.clk_sdram) 1 3 6 NJ 280 NJ 280 NJ 280 NJ 280 NJ 300 NJ
|
||||
preplace netloc INTERCONNECT<net_container>Qsys</net_container>(SLAVE)sysid_qsys.control_slave,(SLAVE)timer.s1,(MASTER)nios2_gen2.instruction_master,(SLAVE)jtag_uart.avalon_jtag_slave,(SLAVE)altpll_0.pll_slave,(SLAVE)nios2_gen2.debug_mem_slave,(SLAVE)led.s1,(SLAVE)EEE_IMGPROC_0.s1,(SLAVE)mipi_pwdn_n.s1,(SLAVE)i2c_opencores_mipi.avalon_slave_0,(MASTER)nios2_gen2.data_master,(SLAVE)TERASIC_AUTO_FOCUS_0.mm_ctrl,(SLAVE)sw.s1,(SLAVE)i2c_opencores_camera.avalon_slave_0,(SLAVE)onchip_memory2_0.s1,(SLAVE)mipi_reset_n.s1,(SLAVE)key.s1) 1 1 7 450 420 850 810 NJ 710 NJ 710 1910 730 2190 770 2580
|
||||
preplace netloc INTERCONNECT<net_container>Qsys</net_container>(SLAVE)sysid_qsys.reset,(SLAVE)onchip_memory2_0.reset1,(SLAVE)timer.reset,(SLAVE)key.reset,(SLAVE)sw.reset,(SLAVE)altpll_0.inclk_interface_reset,(SLAVE)i2c_opencores_camera.clock_reset,(SLAVE)TERASIC_AUTO_FOCUS_0.reset,(SLAVE)i2c_opencores_mipi.clock_reset,(SLAVE)mipi_reset_n.reset,(SLAVE)jtag_uart.reset,(SLAVE)alt_vip_itc_0.is_clk_rst_reset,(SLAVE)sdram.reset,(SLAVE)led.reset,(SLAVE)TERASIC_CAMERA_0.clock_reset_reset,(SLAVE)nios2_gen2.reset,(SLAVE)alt_vip_vfb_0.reset,(SLAVE)EEE_IMGPROC_0.reset,(MASTER)nios2_gen2.debug_reset_request,(SLAVE)mipi_pwdn_n.reset,(SLAVE)uart_0.reset,(MASTER)clk_50.clk_reset) 1 1 7 430 750 830 850 1190 830 1670 730 1890 770 2110 910 2700
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(SLAVE)key.clk,(SLAVE)i2c_opencores_camera.clock,(SLAVE)nios2_gen2.clk,(SLAVE)uart_0.clk,(MASTER)clk_50.clk,(SLAVE)jtag_uart.clk,(SLAVE)onchip_memory2_0.clk1,(SLAVE)altpll_0.inclk_interface,(SLAVE)i2c_opencores_mipi.clock,(SLAVE)sw.clk,(SLAVE)mipi_reset_n.clk,(SLAVE)sysid_qsys.clk,(SLAVE)led.clk,(SLAVE)mipi_pwdn_n.clk,(SLAVE)timer.clk) 1 1 7 410 450 930 400 NJ 400 NJ 400 NJ 400 NJ 400 2660
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)i2c_opencores_camera.export,(SLAVE)Qsys.i2c_opencores_camera_export) 1 0 8 NJ 100 NJ 100 NJ 100 NJ 100 NJ 100 NJ 100 NJ 100 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)led.external_connection,(SLAVE)Qsys.led_external_connection) 1 0 8 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.eee_imgproc_0_conduit_mode,(SLAVE)EEE_IMGPROC_0.conduit_mode) 1 0 7 NJ 300 NJ 300 NJ 410 NJ 410 NJ 410 NJ 410 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.altpll_0_locked_conduit,(SLAVE)altpll_0.locked_conduit) 1 0 3 NJ 280 NJ 280 NJ
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(SLAVE)mipi_pwdn_n.clk,(SLAVE)i2c_opencores_camera.clock,(SLAVE)key.clk,(SLAVE)onchip_memory2_0.clk1,(MASTER)clk_50.clk,(SLAVE)jtag_uart.clk,(SLAVE)mipi_reset_n.clk,(SLAVE)nios2_gen2.clk,(SLAVE)sysid_qsys.clk,(SLAVE)altpll_0.inclk_interface,(SLAVE)i2c_opencores_mipi.clock,(SLAVE)led.clk,(SLAVE)sw.clk,(SLAVE)timer.clk,(SLAVE)uart_interface_0.clock) 1 1 7 410 320 950 380 NJ 340 NJ 300 NJ 300 NJ 300 2640
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.sdram_wire,(SLAVE)sdram.wire) 1 0 8 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)sdram.wire,(SLAVE)Qsys.sdram_wire) 1 0 8 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ 980 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.eee_imgproc_0_conduit_mode,(SLAVE)EEE_IMGPROC_0.conduit_mode) 1 0 7 NJ 490 NJ 490 NJ 550 NJ 550 NJ 550 NJ 550 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)Qsys.clk_sdram,(MASTER)altpll_0.c1) 1 3 6 NJ 220 NJ 220 NJ 220 NJ 220 NJ 160 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)TERASIC_CAMERA_0.conduit_end,(SLAVE)Qsys.terasic_camera_0_conduit_end) 1 0 4 NJ 430 NJ 430 NJ 470 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)mipi_pwdn_n.external_connection,(SLAVE)Qsys.mipi_pwdn_n_external_connection) 1 0 8 NJ 1120 NJ 1120 NJ 1120 NJ 1120 NJ 1120 NJ 1120 NJ 1120 NJ
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(SLAVE)sdram.clk,(SLAVE)alt_vip_itc_0.is_clk_rst,(MASTER)altpll_0.c2,(SLAVE)TERASIC_CAMERA_0.clock_reset,(SLAVE)TERASIC_AUTO_FOCUS_0.clock,(SLAVE)EEE_IMGPROC_0.clock,(SLAVE)alt_vip_vfb_0.clock) 1 3 5 1250 300 1670 730 1870 690 2150 860 2600
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.uart_interface_0_conduit_end,(SLAVE)uart_interface_0.conduit_end) 1 0 2 NJ 360 NJ
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(MASTER)EEE_IMGPROC_0.avalon_streaming_source,(SLAVE)alt_vip_itc_0.din) 1 7 1 2600
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.terasic_auto_focus_0_conduit,(SLAVE)TERASIC_AUTO_FOCUS_0.Conduit) 1 0 6 NJ 460 NJ 460 NJ 570 NJ 570 NJ 570 NJ
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(SLAVE)i2c_opencores_mipi.interrupt_sender,(SLAVE)i2c_opencores_camera.interrupt_sender,(SLAVE)jtag_uart.irq,(MASTER)nios2_gen2.irq,(SLAVE)timer.irq) 1 2 6 NJ 870 NJ 870 NJ 790 NJ 790 NJ 790 2620
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)key.external_connection,(SLAVE)Qsys.key_external_connection) 1 0 8 NJ 710 NJ 710 NJ 830 NJ 730 NJ 770 NJ 750 NJ 750 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.clk,(SLAVE)clk_50.clk_in) 1 0 1 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)altpll_0.areset_conduit,(SLAVE)Qsys.altpll_0_areset_conduit) 1 0 3 NJ 260 NJ 260 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.key_external_connection,(SLAVE)key.external_connection) 1 0 8 NJ 370 NJ 370 NJ 450 NJ 450 NJ 450 NJ 450 NJ 650 NJ
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(MASTER)EEE_IMGPROC_0.avalon_streaming_source,(SLAVE)alt_vip_itc_0.din) 1 7 1 2620
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.led_external_connection,(SLAVE)led.external_connection) 1 0 8 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ 1420 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.uart_0_rx_tx,(SLAVE)uart_0.external_connection) 1 0 3 NJ 510 NJ 510 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.terasic_auto_focus_0_conduit,(SLAVE)TERASIC_AUTO_FOCUS_0.Conduit) 1 0 6 NJ 690 NJ 690 NJ 690 NJ 690 NJ 570 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.i2c_opencores_mipi_export,(SLAVE)i2c_opencores_mipi.export) 1 0 8 NJ 240 NJ 240 NJ 240 NJ 240 NJ 240 NJ 240 NJ 240 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.alt_vip_itc_0_clocked_video,(SLAVE)alt_vip_itc_0.clocked_video) 1 0 8 NJ 890 NJ 890 NJ 890 NJ 890 NJ 820 NJ 820 NJ 820 NJ
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(SLAVE)TERASIC_AUTO_FOCUS_0.din,(MASTER)alt_vip_vfb_0.dout) 1 5 1 1890
|
||||
preplace netloc FAN_IN<net_container>Qsys</net_container>(SLAVE)sdram.s1,(MASTER)alt_vip_vfb_0.write_master,(MASTER)alt_vip_vfb_0.read_master) 1 5 3 1890 960 NJ 960 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)clk_50.clk_in,(SLAVE)Qsys.clk) 1 0 1 NJ
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(SLAVE)EEE_IMGPROC_0.avalon_streaming_sink,(MASTER)TERASIC_AUTO_FOCUS_0.dout) 1 6 1 N
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(SLAVE)alt_vip_vfb_0.din,(MASTER)TERASIC_CAMERA_0.avalon_streaming_source) 1 4 1 1630
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(MASTER)nios2_gen2.irq,(SLAVE)jtag_uart.irq,(SLAVE)i2c_opencores_mipi.interrupt_sender,(SLAVE)uart_0.irq,(SLAVE)timer.irq,(SLAVE)i2c_opencores_camera.interrupt_sender) 1 2 6 950 530 NJ 530 NJ 530 NJ 530 NJ 670 2620
|
||||
preplace netloc FAN_OUT<net_container>Qsys</net_container>(MASTER)altpll_0.c2,(SLAVE)EEE_IMGPROC_0.clock,(SLAVE)sdram.clk,(SLAVE)TERASIC_CAMERA_0.clock_reset,(SLAVE)alt_vip_itc_0.is_clk_rst,(SLAVE)TERASIC_AUTO_FOCUS_0.clock,(SLAVE)alt_vip_vfb_0.clock) 1 3 5 1190 730 1630 710 1910 730 2150 890 2680
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(SLAVE)EEE_IMGPROC_0.avalon_streaming_sink,(MASTER)TERASIC_AUTO_FOCUS_0.dout) 1 6 1 2110
|
||||
preplace netloc INTERCONNECT<net_container>Qsys</net_container>(SLAVE)i2c_opencores_mipi.avalon_slave_0,(SLAVE)nios2_gen2.debug_mem_slave,(SLAVE)jtag_uart.avalon_jtag_slave,(SLAVE)led.s1,(MASTER)nios2_gen2.instruction_master,(SLAVE)mipi_reset_n.s1,(SLAVE)onchip_memory2_0.s1,(SLAVE)uart_0.s1,(SLAVE)sysid_qsys.control_slave,(SLAVE)sw.s1,(SLAVE)altpll_0.pll_slave,(SLAVE)mipi_pwdn_n.s1,(SLAVE)TERASIC_AUTO_FOCUS_0.mm_ctrl,(SLAVE)timer.s1,(SLAVE)i2c_opencores_camera.avalon_slave_0,(SLAVE)key.s1,(MASTER)nios2_gen2.data_master,(SLAVE)EEE_IMGPROC_0.s1) 1 1 7 430 470 890 710 NJ 710 NJ 610 1870 790 2170 690 2580
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)sw.external_connection,(SLAVE)Qsys.sw_external_connection) 1 0 8 NJ 1320 NJ 1320 NJ 1320 NJ 1320 NJ 1320 NJ 1320 NJ 1320 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.mipi_reset_n_external_connection,(SLAVE)mipi_reset_n.external_connection) 1 0 8 NJ 1220 NJ 1220 NJ 1220 NJ 1220 NJ 1220 NJ 1220 NJ 1220 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)altpll_0.c3,(MASTER)Qsys.clk_vga) 1 3 6 NJ 320 NJ 320 NJ 320 NJ 320 NJ 320 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.altpll_0_areset_conduit,(SLAVE)altpll_0.areset_conduit) 1 0 3 NJ 260 NJ 260 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)Qsys.d8m_xclkin,(MASTER)altpll_0.c4) 1 3 6 NJ 220 NJ 220 NJ 220 NJ 220 NJ 160 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.terasic_camera_0_conduit_end,(SLAVE)TERASIC_CAMERA_0.conduit_end) 1 0 4 NJ 480 NJ 480 NJ 790 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)altpll_0.c4,(MASTER)Qsys.d8m_xclkin) 1 3 6 NJ 380 NJ 380 NJ 380 NJ 280 NJ 320 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(MASTER)altpll_0.c3,(MASTER)Qsys.clk_vga) 1 3 6 NJ 320 NJ 320 NJ 320 NJ 260 NJ 300 NJ
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(MASTER)TERASIC_CAMERA_0.avalon_streaming_source,(SLAVE)alt_vip_vfb_0.din) 1 4 1 1650
|
||||
preplace netloc POINT_TO_POINT<net_container>Qsys</net_container>(MASTER)alt_vip_vfb_0.dout,(SLAVE)TERASIC_AUTO_FOCUS_0.din) 1 5 1 1890
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)Qsys.reset,(SLAVE)clk_50.clk_in_reset) 1 0 1 NJ
|
||||
preplace netloc INTERCONNECT<net_container>Qsys</net_container>(SLAVE)sw.reset,(SLAVE)timer.reset,(SLAVE)onchip_memory2_0.reset1,(SLAVE)key.reset,(SLAVE)alt_vip_vfb_0.reset,(SLAVE)uart_interface_0.reset,(SLAVE)mipi_pwdn_n.reset,(SLAVE)i2c_opencores_camera.clock_reset,(SLAVE)led.reset,(SLAVE)TERASIC_AUTO_FOCUS_0.reset,(SLAVE)TERASIC_CAMERA_0.clock_reset_reset,(MASTER)clk_50.clk_reset,(SLAVE)jtag_uart.reset,(MASTER)nios2_gen2.debug_reset_request,(SLAVE)EEE_IMGPROC_0.reset,(SLAVE)sysid_qsys.reset,(SLAVE)alt_vip_itc_0.is_clk_rst_reset,(SLAVE)sdram.reset,(SLAVE)nios2_gen2.reset,(SLAVE)i2c_opencores_mipi.clock_reset,(SLAVE)altpll_0.inclk_interface_reset,(SLAVE)mipi_reset_n.reset) 1 1 7 430 440 910 850 1290 690 1690 750 1930 710 2170 880 2680
|
||||
levelinfo -pg 1 0 200 3000
|
||||
levelinfo -hier Qsys 210 240 590 1020 1340 1720 2020 2320 2750 2900
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)altpll_0.locked_conduit,(SLAVE)Qsys.altpll_0_locked_conduit) 1 0 3 NJ 320 NJ 320 NJ
|
||||
preplace netloc EXPORT<net_container>Qsys</net_container>(SLAVE)alt_vip_itc_0.clocked_video,(SLAVE)Qsys.alt_vip_itc_0_clocked_video) 1 0 8 NJ 870 NJ 870 NJ 870 NJ 870 NJ 870 NJ 870 NJ 870 NJ
|
||||
preplace netloc FAN_IN<net_container>Qsys</net_container>(MASTER)alt_vip_vfb_0.write_master,(MASTER)alt_vip_vfb_0.read_master,(SLAVE)sdram.s1) 1 5 3 1850 960 NJ 960 NJ
|
||||
levelinfo -pg 1 0 200 3040
|
||||
levelinfo -hier Qsys 210 240 590 980 1300 1700 1980 2320 2790 2940
|
||||
|
|
|
@ -1,2 +1,2 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<filters version="16.0" />
|
||||
<filters version="16.1" />
|
||||
|
|
|
@ -3,12 +3,13 @@
|
|||
<debug showDebugMenu="0" />
|
||||
<systemtable filter="All Interfaces">
|
||||
<columns>
|
||||
<connections preferredWidth="319" />
|
||||
<connections preferredWidth="143" />
|
||||
<irq preferredWidth="34" />
|
||||
<name preferredWidth="201" />
|
||||
<export preferredWidth="267" />
|
||||
</columns>
|
||||
</systemtable>
|
||||
<library expandedCategories="Library,Project" />
|
||||
<window width="2560" height="1377" x="0" y="23" />
|
||||
<library
|
||||
expandedCategories="Project,Library/Interface Protocols,Library,Library/Interface Protocols/Serial" />
|
||||
<window width="1936" height="1063" x="0" y="0" />
|
||||
</preferences>
|
||||
|
|
|
@ -6,7 +6,7 @@ set_global_assignment -name FAMILY "MAX 10"
|
|||
set_global_assignment -name DEVICE 10M50DAF484C7G
|
||||
set_global_assignment -name TOP_LEVEL_ENTITY DE10_LITE_D8M_VIP
|
||||
set_global_assignment -name ORIGINAL_QUARTUS_VERSION 15.1.0
|
||||
set_global_assignment -name LAST_QUARTUS_VERSION 16.0.2
|
||||
set_global_assignment -name LAST_QUARTUS_VERSION "16.1.0 Lite Edition"
|
||||
set_global_assignment -name PROJECT_CREATION_TIME_DATE "15:21:37 AUGUST 23,2016"
|
||||
set_global_assignment -name DEVICE_FILTER_PACKAGE FBGA
|
||||
set_global_assignment -name DEVICE_FILTER_PIN_COUNT 484
|
||||
|
|
Binary file not shown.
|
@ -178,14 +178,8 @@ Qsys u0 (
|
|||
|
||||
.eee_imgproc_0_conduit_mode_new_signal (SW[0]),
|
||||
|
||||
// .uart_interface_0_conduit_end_rx (ARDUINO_IO[13]), // input from ESP32 RX2pin
|
||||
// .uart_interface_0_conduit_end_rx_data (), // output [7:0]
|
||||
// .uart_interface_0_conduit_end_rx_valid (), // output
|
||||
//
|
||||
// .uart_interface_0_conduit_end_tx (ARDUINO_IO[12]), // output to ESP32 TX2pin
|
||||
// .uart_interface_0_conduit_end_tx_data (), // input [7:0]
|
||||
// .uart_interface_0_conduit_end_tx_transmit (), // input
|
||||
// .uart_interface_0_conduit_end_tx_ready () // output
|
||||
.uart_0_rx_tx_rxd (ARDUINO_IO[1]), // uart_0_rx_tx.rxd
|
||||
.uart_0_rx_tx_txd (ARDUINO_IO[0]) //
|
||||
);
|
||||
|
||||
FpsMonitor uFps(
|
||||
|
|
|
@ -1,13 +0,0 @@
|
|||
/* Quartus Prime Version 16.1.0 Build 196 10/24/2016 SJ Lite Edition */
|
||||
JedecChain;
|
||||
FileRevision(JESD32A);
|
||||
DefaultMfr(6E);
|
||||
|
||||
P ActionCode(Cfg)
|
||||
Device PartName(10M50DAF484) Path("C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/") File("DE10_LITE_D8M_VIP_time_limited.sof") MfrSpec(OpMask(1));
|
||||
|
||||
ChainEnd;
|
||||
|
||||
AlteraBegin;
|
||||
ChainType(JTAG);
|
||||
AlteraEnd;
|
Binary file not shown.
|
@ -13,9 +13,14 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "19";
|
||||
value = "18";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element Qsys
|
||||
{
|
||||
|
@ -45,9 +50,14 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "16";
|
||||
value = "17";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element TERASIC_AUTO_FOCUS_0.mm_ctrl
|
||||
{
|
||||
|
@ -61,38 +71,58 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "13";
|
||||
value = "14";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element alt_vip_itc_0
|
||||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "17";
|
||||
value = "19";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element alt_vip_vfb_0
|
||||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "14";
|
||||
value = "16";
|
||||
type = "int";
|
||||
}
|
||||
datum megawizard_uipreferences
|
||||
{
|
||||
value = "{output_directory=F:\\Board_Proj\\D8M\\DE10_LITE_D8M_VIP, output_language=VERILOG}";
|
||||
value = "{output_directory=F:\\Ed\\Stuff\\EEE2Rover\\DE10_LITE_D8M_VIP_16, output_language=VERILOG}";
|
||||
type = "String";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element altpll_0
|
||||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "18";
|
||||
value = "20";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element altpll_0.pll_slave
|
||||
{
|
||||
|
@ -114,7 +144,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "5";
|
||||
value = "6";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -130,7 +160,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "4";
|
||||
value = "5";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -162,7 +192,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "8";
|
||||
value = "9";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -178,7 +208,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "6";
|
||||
value = "7";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -194,7 +224,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "10";
|
||||
value = "11";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -210,7 +240,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "9";
|
||||
value = "10";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -261,6 +291,11 @@
|
|||
value = "15";
|
||||
type = "int";
|
||||
}
|
||||
datum sopceditor_expanded
|
||||
{
|
||||
value = "0";
|
||||
type = "boolean";
|
||||
}
|
||||
}
|
||||
element sdram.s1
|
||||
{
|
||||
|
@ -274,7 +309,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "7";
|
||||
value = "8";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -290,7 +325,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "11";
|
||||
value = "12";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -306,7 +341,7 @@
|
|||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "12";
|
||||
value = "13";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
|
@ -318,6 +353,14 @@
|
|||
type = "String";
|
||||
}
|
||||
}
|
||||
element uart_0
|
||||
{
|
||||
datum _sortIndex
|
||||
{
|
||||
value = "4";
|
||||
type = "int";
|
||||
}
|
||||
}
|
||||
}
|
||||
]]></parameter>
|
||||
<parameter name="clockCrossingAdapter" value="HANDSHAKE" />
|
||||
|
@ -424,6 +467,11 @@
|
|||
internal="TERASIC_CAMERA_0.conduit_end"
|
||||
type="conduit"
|
||||
dir="end" />
|
||||
<interface
|
||||
name="uart_0_rx_tx"
|
||||
internal="uart_0.external_connection"
|
||||
type="conduit"
|
||||
dir="end" />
|
||||
<module name="EEE_IMGPROC_0" kind="EEE_IMGPROC" version="1.0" enabled="1" />
|
||||
<module
|
||||
name="TERASIC_AUTO_FOCUS_0"
|
||||
|
@ -767,7 +815,7 @@
|
|||
<parameter name="dataAddrWidth" value="19" />
|
||||
<parameter name="dataMasterHighPerformanceAddrWidth" value="1" />
|
||||
<parameter name="dataMasterHighPerformanceMapParam" value="" />
|
||||
<parameter name="dataSlaveMapParam"><![CDATA[<address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x386A0' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /><slave name='timer.s1' start='0x41000' end='0x41020' type='altera_avalon_timer.s1' /><slave name='TERASIC_AUTO_FOCUS_0.mm_ctrl' start='0x41020' end='0x41040' type='TERASIC_AUTO_FOCUS.mm_ctrl' /><slave name='i2c_opencores_camera.avalon_slave_0' start='0x41040' end='0x41060' type='i2c_opencores.avalon_slave_0' /><slave name='i2c_opencores_mipi.avalon_slave_0' start='0x41060' end='0x41080' type='i2c_opencores.avalon_slave_0' /><slave name='mipi_pwdn_n.s1' start='0x41080' end='0x41090' type='altera_avalon_pio.s1' /><slave name='mipi_reset_n.s1' start='0x41090' end='0x410A0' type='altera_avalon_pio.s1' /><slave name='key.s1' start='0x410A0' end='0x410B0' type='altera_avalon_pio.s1' /><slave name='sw.s1' start='0x410B0' end='0x410C0' type='altera_avalon_pio.s1' /><slave name='led.s1' start='0x410C0' end='0x410D0' type='altera_avalon_pio.s1' /><slave name='altpll_0.pll_slave' start='0x410D0' end='0x410E0' type='altpll.pll_slave' /><slave name='sysid_qsys.control_slave' start='0x410E0' end='0x410E8' type='altera_avalon_sysid_qsys.control_slave' /><slave name='jtag_uart.avalon_jtag_slave' start='0x410E8' end='0x410F0' type='altera_avalon_jtag_uart.avalon_jtag_slave' /><slave name='EEE_IMGPROC_0.s1' start='0x42000' end='0x42020' type='EEE_IMGPROC.s1' /></address-map>]]></parameter>
|
||||
<parameter name="dataSlaveMapParam"><![CDATA[<address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x40000' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /><slave name='timer.s1' start='0x41000' end='0x41020' type='altera_avalon_timer.s1' /><slave name='TERASIC_AUTO_FOCUS_0.mm_ctrl' start='0x41020' end='0x41040' type='TERASIC_AUTO_FOCUS.mm_ctrl' /><slave name='i2c_opencores_camera.avalon_slave_0' start='0x41040' end='0x41060' type='i2c_opencores.avalon_slave_0' /><slave name='i2c_opencores_mipi.avalon_slave_0' start='0x41060' end='0x41080' type='i2c_opencores.avalon_slave_0' /><slave name='mipi_pwdn_n.s1' start='0x41080' end='0x41090' type='altera_avalon_pio.s1' /><slave name='mipi_reset_n.s1' start='0x41090' end='0x410A0' type='altera_avalon_pio.s1' /><slave name='key.s1' start='0x410A0' end='0x410B0' type='altera_avalon_pio.s1' /><slave name='sw.s1' start='0x410B0' end='0x410C0' type='altera_avalon_pio.s1' /><slave name='led.s1' start='0x410C0' end='0x410D0' type='altera_avalon_pio.s1' /><slave name='altpll_0.pll_slave' start='0x410D0' end='0x410E0' type='altpll.pll_slave' /><slave name='sysid_qsys.control_slave' start='0x410E0' end='0x410E8' type='altera_avalon_sysid_qsys.control_slave' /><slave name='jtag_uart.avalon_jtag_slave' start='0x410E8' end='0x410F0' type='altera_avalon_jtag_uart.avalon_jtag_slave' /><slave name='EEE_IMGPROC_0.s1' start='0x42000' end='0x42020' type='EEE_IMGPROC.s1' /><slave name='uart_0.s1' start='0x42020' end='0x42040' type='altera_avalon_uart.s1' /></address-map>]]></parameter>
|
||||
<parameter name="data_master_high_performance_paddr_base" value="0" />
|
||||
<parameter name="data_master_high_performance_paddr_size" value="0" />
|
||||
<parameter name="data_master_paddr_base" value="0" />
|
||||
|
@ -806,14 +854,14 @@
|
|||
<parameter name="icache_tagramBlockType" value="Automatic" />
|
||||
<parameter name="impl" value="Fast" />
|
||||
<parameter name="instAddrWidth" value="19" />
|
||||
<parameter name="instSlaveMapParam"><![CDATA[<address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x386A0' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /></address-map>]]></parameter>
|
||||
<parameter name="instSlaveMapParam"><![CDATA[<address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x40000' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /></address-map>]]></parameter>
|
||||
<parameter name="instructionMasterHighPerformanceAddrWidth" value="1" />
|
||||
<parameter name="instructionMasterHighPerformanceMapParam" value="" />
|
||||
<parameter name="instruction_master_high_performance_paddr_base" value="0" />
|
||||
<parameter name="instruction_master_high_performance_paddr_size" value="0" />
|
||||
<parameter name="instruction_master_paddr_base" value="0" />
|
||||
<parameter name="instruction_master_paddr_size" value="0" />
|
||||
<parameter name="internalIrqMaskSystemInfo" value="15" />
|
||||
<parameter name="internalIrqMaskSystemInfo" value="31" />
|
||||
<parameter name="io_regionbase" value="0" />
|
||||
<parameter name="io_regionsize" value="0" />
|
||||
<parameter name="master_addr_map" value="false" />
|
||||
|
@ -945,7 +993,7 @@
|
|||
<parameter name="initMemContent" value="false" />
|
||||
<parameter name="initializationFileName" value="onchip_mem.hex" />
|
||||
<parameter name="instanceID" value="NONE" />
|
||||
<parameter name="memorySize" value="100000" />
|
||||
<parameter name="memorySize" value="131072" />
|
||||
<parameter name="readDuringWriteMode" value="DONT_CARE" />
|
||||
<parameter name="resetrequest_enabled" value="true" />
|
||||
<parameter name="simAllowMRAMContentsFile" value="false" />
|
||||
|
@ -1019,6 +1067,22 @@
|
|||
<parameter name="timeoutPulseOutput" value="false" />
|
||||
<parameter name="watchdogPulse" value="2" />
|
||||
</module>
|
||||
<module name="uart_0" kind="altera_avalon_uart" version="16.1" enabled="1">
|
||||
<parameter name="baud" value="115200" />
|
||||
<parameter name="clockRate" value="50000000" />
|
||||
<parameter name="dataBits" value="8" />
|
||||
<parameter name="fixedBaud" value="true" />
|
||||
<parameter name="parity" value="NONE" />
|
||||
<parameter name="simCharStream" value="" />
|
||||
<parameter name="simInteractiveInputEnable" value="false" />
|
||||
<parameter name="simInteractiveOutputEnable" value="false" />
|
||||
<parameter name="simTrueBaud" value="false" />
|
||||
<parameter name="stopBits" value="1" />
|
||||
<parameter name="syncRegDepth" value="2" />
|
||||
<parameter name="useCtsRts" value="false" />
|
||||
<parameter name="useEopRegister" value="false" />
|
||||
<parameter name="useRelativePathForSimFile" value="false" />
|
||||
</module>
|
||||
<connection
|
||||
kind="avalon"
|
||||
version="16.1"
|
||||
|
@ -1154,6 +1218,15 @@
|
|||
<parameter name="baseAddress" value="0x00042000" />
|
||||
<parameter name="defaultConnection" value="false" />
|
||||
</connection>
|
||||
<connection
|
||||
kind="avalon"
|
||||
version="16.1"
|
||||
start="nios2_gen2.data_master"
|
||||
end="uart_0.s1">
|
||||
<parameter name="arbitrationPriority" value="1" />
|
||||
<parameter name="baseAddress" value="0x00042020" />
|
||||
<parameter name="defaultConnection" value="false" />
|
||||
</connection>
|
||||
<connection
|
||||
kind="avalon"
|
||||
version="16.1"
|
||||
|
@ -1245,6 +1318,7 @@
|
|||
<connection kind="clock" version="16.1" start="clk_50.clk" end="mipi_reset_n.clk" />
|
||||
<connection kind="clock" version="16.1" start="clk_50.clk" end="mipi_pwdn_n.clk" />
|
||||
<connection kind="clock" version="16.1" start="clk_50.clk" end="nios2_gen2.clk" />
|
||||
<connection kind="clock" version="16.1" start="clk_50.clk" end="uart_0.clk" />
|
||||
<connection
|
||||
kind="clock"
|
||||
version="16.1"
|
||||
|
@ -1293,6 +1367,13 @@
|
|||
end="timer.irq">
|
||||
<parameter name="irqNumber" value="3" />
|
||||
</connection>
|
||||
<connection
|
||||
kind="interrupt"
|
||||
version="16.1"
|
||||
start="nios2_gen2.irq"
|
||||
end="uart_0.irq">
|
||||
<parameter name="irqNumber" value="4" />
|
||||
</connection>
|
||||
<connection
|
||||
kind="reset"
|
||||
version="16.1"
|
||||
|
@ -1371,6 +1452,11 @@
|
|||
version="16.1"
|
||||
start="clk_50.clk_reset"
|
||||
end="EEE_IMGPROC_0.reset" />
|
||||
<connection
|
||||
kind="reset"
|
||||
version="16.1"
|
||||
start="clk_50.clk_reset"
|
||||
end="uart_0.reset" />
|
||||
<connection
|
||||
kind="reset"
|
||||
version="16.1"
|
||||
|
@ -1461,6 +1547,11 @@
|
|||
version="16.1"
|
||||
start="nios2_gen2.debug_reset_request"
|
||||
end="EEE_IMGPROC_0.reset" />
|
||||
<connection
|
||||
kind="reset"
|
||||
version="16.1"
|
||||
start="nios2_gen2.debug_reset_request"
|
||||
end="uart_0.reset" />
|
||||
<connection
|
||||
kind="reset"
|
||||
version="16.1"
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -21,9 +21,9 @@ agreement for further details.
|
|||
*/
|
||||
(header "symbol" (version "1.1"))
|
||||
(symbol
|
||||
(rect 0 0 576 1072)
|
||||
(rect 0 0 576 1128)
|
||||
(text "Qsys" (rect 273 -1 295 11)(font "Arial" (font_size 10)))
|
||||
(text "inst" (rect 8 1056 20 1068)(font "Arial" ))
|
||||
(text "inst" (rect 8 1112 20 1124)(font "Arial" ))
|
||||
(port
|
||||
(pt 0 72)
|
||||
(input)
|
||||
|
@ -108,6 +108,13 @@ agreement for further details.
|
|||
(text "terasic_camera_0_conduit_end_PIXCLK" (rect 4 1029 214 1040)(font "Arial" (font_size 8)))
|
||||
(line (pt 0 1040)(pt 240 1040)(line_width 1))
|
||||
)
|
||||
(port
|
||||
(pt 0 1080)
|
||||
(input)
|
||||
(text "uart_0_rx_tx_rxd" (rect 0 0 71 12)(font "Arial" (font_size 8)))
|
||||
(text "uart_0_rx_tx_rxd" (rect 4 1069 100 1080)(font "Arial" (font_size 8)))
|
||||
(line (pt 0 1080)(pt 240 1080)(line_width 1))
|
||||
)
|
||||
(port
|
||||
(pt 0 88)
|
||||
(output)
|
||||
|
@ -269,6 +276,13 @@ agreement for further details.
|
|||
(text "sdram_wire_we_n" (rect 4 829 94 840)(font "Arial" (font_size 8)))
|
||||
(line (pt 0 840)(pt 240 840)(line_width 1))
|
||||
)
|
||||
(port
|
||||
(pt 0 1096)
|
||||
(output)
|
||||
(text "uart_0_rx_tx_txd" (rect 0 0 70 12)(font "Arial" (font_size 8)))
|
||||
(text "uart_0_rx_tx_txd" (rect 4 1085 100 1096)(font "Arial" (font_size 8)))
|
||||
(line (pt 0 1096)(pt 240 1096)(line_width 1))
|
||||
)
|
||||
(port
|
||||
(pt 0 400)
|
||||
(bidir)
|
||||
|
@ -380,11 +394,14 @@ agreement for further details.
|
|||
(text "FVAL" (rect 245 1003 514 2016)(font "Arial" (color 0 0 0)))
|
||||
(text "LVAL" (rect 245 1019 514 2048)(font "Arial" (color 0 0 0)))
|
||||
(text "PIXCLK" (rect 245 1035 526 2080)(font "Arial" (color 0 0 0)))
|
||||
(text " Qsys " (rect 550 1056 1136 2122)(font "Arial" ))
|
||||
(text "uart_0_rx_tx" (rect 166 1051 404 2115)(font "Arial" (color 128 0 0)(font_size 9)))
|
||||
(text "rxd" (rect 245 1075 508 2160)(font "Arial" (color 0 0 0)))
|
||||
(text "txd" (rect 245 1091 508 2192)(font "Arial" (color 0 0 0)))
|
||||
(text " Qsys " (rect 550 1112 1136 2234)(font "Arial" ))
|
||||
(line (pt 240 32)(pt 336 32)(line_width 1))
|
||||
(line (pt 336 32)(pt 336 1056)(line_width 1))
|
||||
(line (pt 240 1056)(pt 336 1056)(line_width 1))
|
||||
(line (pt 240 32)(pt 240 1056)(line_width 1))
|
||||
(line (pt 336 32)(pt 336 1112)(line_width 1))
|
||||
(line (pt 240 1112)(pt 336 1112)(line_width 1))
|
||||
(line (pt 240 32)(pt 240 1112)(line_width 1))
|
||||
(line (pt 241 52)(pt 241 204)(line_width 1))
|
||||
(line (pt 242 52)(pt 242 204)(line_width 1))
|
||||
(line (pt 241 220)(pt 241 244)(line_width 1))
|
||||
|
@ -423,9 +440,11 @@ agreement for further details.
|
|||
(line (pt 242 900)(pt 242 956)(line_width 1))
|
||||
(line (pt 241 972)(pt 241 1044)(line_width 1))
|
||||
(line (pt 242 972)(pt 242 1044)(line_width 1))
|
||||
(line (pt 241 1060)(pt 241 1100)(line_width 1))
|
||||
(line (pt 242 1060)(pt 242 1100)(line_width 1))
|
||||
(line (pt 0 0)(pt 576 0)(line_width 1))
|
||||
(line (pt 576 0)(pt 576 1072)(line_width 1))
|
||||
(line (pt 0 1072)(pt 576 1072)(line_width 1))
|
||||
(line (pt 0 0)(pt 0 1072)(line_width 1))
|
||||
(line (pt 576 0)(pt 576 1128)(line_width 1))
|
||||
(line (pt 0 1128)(pt 576 1128)(line_width 1))
|
||||
(line (pt 0 0)(pt 0 1128)(line_width 1))
|
||||
)
|
||||
)
|
||||
|
|
|
@ -41,7 +41,9 @@
|
|||
terasic_camera_0_conduit_end_D : in std_logic_vector(11 downto 0) := (others => 'X'); -- D
|
||||
terasic_camera_0_conduit_end_FVAL : in std_logic := 'X'; -- FVAL
|
||||
terasic_camera_0_conduit_end_LVAL : in std_logic := 'X'; -- LVAL
|
||||
terasic_camera_0_conduit_end_PIXCLK : in std_logic := 'X' -- PIXCLK
|
||||
terasic_camera_0_conduit_end_PIXCLK : in std_logic := 'X'; -- PIXCLK
|
||||
uart_0_rx_tx_rxd : in std_logic := 'X'; -- rxd
|
||||
uart_0_rx_tx_txd : out std_logic -- txd
|
||||
);
|
||||
end component Qsys;
|
||||
|
||||
|
|
|
@ -67,7 +67,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</table>
|
||||
<table class="blueBar">
|
||||
<tr>
|
||||
<td class="l">2021.05.27.17:50:16</td>
|
||||
<td class="l">2021.06.03.15:09:34</td>
|
||||
<td class="r">Datasheet</td>
|
||||
</tr>
|
||||
</table>
|
||||
|
@ -137,7 +137,10 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</a> altera_avalon_sysid_qsys 16.1
|
||||
<br/>  
|
||||
<a href="#module_timer"><b>timer</b>
|
||||
</a> altera_avalon_timer 16.1</span>
|
||||
</a> altera_avalon_timer 16.1
|
||||
<br/>  
|
||||
<a href="#module_uart_0"><b>uart_0</b>
|
||||
</a> altera_avalon_uart 16.1</span>
|
||||
</div>
|
||||
</div>
|
||||
<div style="width:100% ; height:10px"> </div>
|
||||
|
@ -432,6 +435,23 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
<td class="addr"><span style="color:#989898">0x</span>00041000</td>
|
||||
<td class="empty"></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="slavemodule"> 
|
||||
<a href="#module_uart_0"><b>uart_0</b>
|
||||
</a>
|
||||
</td>
|
||||
<td class="empty"></td>
|
||||
<td class="empty"></td>
|
||||
<td class="empty"></td>
|
||||
<td class="empty"></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="slaveb">s1 </td>
|
||||
<td class="empty"></td>
|
||||
<td class="empty"></td>
|
||||
<td class="addr"><span style="color:#989898">0x</span>00042020</td>
|
||||
<td class="empty"></td>
|
||||
</tr>
|
||||
</table>
|
||||
<a name="module_EEE_IMGPROC_0"> </a>
|
||||
<div>
|
||||
|
@ -3115,7 +3135,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
<a href="#module_clk_50">clk_50</a>
|
||||
</td>
|
||||
<td class="from">clk  </td>
|
||||
<td class="main" rowspan="93">nios2_gen2</td>
|
||||
<td class="main" rowspan="100">nios2_gen2</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  clk</td>
|
||||
|
@ -3530,6 +3550,42 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
<tr style="height:6px">
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="from">data_master  </td>
|
||||
<td class="neighbor" rowspan="6">
|
||||
<a href="#module_uart_0">uart_0</a>
|
||||
</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="to">  s1</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="from">irq  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="to">  irq</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="from">debug_reset_request  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
<td class="to">  reset</td>
|
||||
</tr>
|
||||
<tr style="height:6px">
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td></td>
|
||||
<td></td>
|
||||
|
@ -4282,7 +4338,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">instSlaveMapParam</td>
|
||||
<td class="parametervalue"><address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x386A0' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /></address-map></td>
|
||||
<td class="parametervalue"><address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x40000' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /></address-map></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">faSlaveMapParam</td>
|
||||
|
@ -4290,7 +4346,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">dataSlaveMapParam</td>
|
||||
<td class="parametervalue"><address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x386A0' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /><slave name='timer.s1' start='0x41000' end='0x41020' type='altera_avalon_timer.s1' /><slave name='TERASIC_AUTO_FOCUS_0.mm_ctrl' start='0x41020' end='0x41040' type='TERASIC_AUTO_FOCUS.mm_ctrl' /><slave name='i2c_opencores_camera.avalon_slave_0' start='0x41040' end='0x41060' type='i2c_opencores.avalon_slave_0' /><slave name='i2c_opencores_mipi.avalon_slave_0' start='0x41060' end='0x41080' type='i2c_opencores.avalon_slave_0' /><slave name='mipi_pwdn_n.s1' start='0x41080' end='0x41090' type='altera_avalon_pio.s1' /><slave name='mipi_reset_n.s1' start='0x41090' end='0x410A0' type='altera_avalon_pio.s1' /><slave name='key.s1' start='0x410A0' end='0x410B0' type='altera_avalon_pio.s1' /><slave name='sw.s1' start='0x410B0' end='0x410C0' type='altera_avalon_pio.s1' /><slave name='led.s1' start='0x410C0' end='0x410D0' type='altera_avalon_pio.s1' /><slave name='altpll_0.pll_slave' start='0x410D0' end='0x410E0' type='altpll.pll_slave' /><slave name='sysid_qsys.control_slave' start='0x410E0' end='0x410E8' type='altera_avalon_sysid_qsys.control_slave' /><slave name='jtag_uart.avalon_jtag_slave' start='0x410E8' end='0x410F0' type='altera_avalon_jtag_uart.avalon_jtag_slave' /><slave name='EEE_IMGPROC_0.s1' start='0x42000' end='0x42020' type='EEE_IMGPROC.s1' /></address-map></td>
|
||||
<td class="parametervalue"><address-map><slave name='onchip_memory2_0.s1' start='0x20000' end='0x40000' type='altera_avalon_onchip_memory2.s1' /><slave name='nios2_gen2.debug_mem_slave' start='0x40800' end='0x41000' type='altera_nios2_gen2.debug_mem_slave' /><slave name='timer.s1' start='0x41000' end='0x41020' type='altera_avalon_timer.s1' /><slave name='TERASIC_AUTO_FOCUS_0.mm_ctrl' start='0x41020' end='0x41040' type='TERASIC_AUTO_FOCUS.mm_ctrl' /><slave name='i2c_opencores_camera.avalon_slave_0' start='0x41040' end='0x41060' type='i2c_opencores.avalon_slave_0' /><slave name='i2c_opencores_mipi.avalon_slave_0' start='0x41060' end='0x41080' type='i2c_opencores.avalon_slave_0' /><slave name='mipi_pwdn_n.s1' start='0x41080' end='0x41090' type='altera_avalon_pio.s1' /><slave name='mipi_reset_n.s1' start='0x41090' end='0x410A0' type='altera_avalon_pio.s1' /><slave name='key.s1' start='0x410A0' end='0x410B0' type='altera_avalon_pio.s1' /><slave name='sw.s1' start='0x410B0' end='0x410C0' type='altera_avalon_pio.s1' /><slave name='led.s1' start='0x410C0' end='0x410D0' type='altera_avalon_pio.s1' /><slave name='altpll_0.pll_slave' start='0x410D0' end='0x410E0' type='altpll.pll_slave' /><slave name='sysid_qsys.control_slave' start='0x410E0' end='0x410E8' type='altera_avalon_sysid_qsys.control_slave' /><slave name='jtag_uart.avalon_jtag_slave' start='0x410E8' end='0x410F0' type='altera_avalon_jtag_uart.avalon_jtag_slave' /><slave name='EEE_IMGPROC_0.s1' start='0x42000' end='0x42020' type='EEE_IMGPROC.s1' /><slave name='uart_0.s1' start='0x42020' end='0x42040' type='altera_avalon_uart.s1' /></address-map></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">tightlyCoupledDataMaster0MapParam</td>
|
||||
|
@ -4342,7 +4398,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">internalIrqMaskSystemInfo</td>
|
||||
<td class="parametervalue">15</td>
|
||||
<td class="parametervalue">31</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">customInstSlavesSystemInfo</td>
|
||||
|
@ -4632,7 +4688,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">memorySize</td>
|
||||
<td class="parametervalue">100000</td>
|
||||
<td class="parametervalue">131072</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">readDuringWriteMode</td>
|
||||
|
@ -4793,7 +4849,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">SIZE_VALUE</td>
|
||||
<td class="parametervalue">100000</td>
|
||||
<td class="parametervalue">131072</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">WRITABLE</td>
|
||||
|
@ -5358,7 +5414,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">timestamp</td>
|
||||
<td class="parametervalue">1622134216</td>
|
||||
<td class="parametervalue">1622729373</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">deviceFamily</td>
|
||||
|
@ -5383,7 +5439,7 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">TIMESTAMP</td>
|
||||
<td class="parametervalue">1622134216</td>
|
||||
<td class="parametervalue">1622729373</td>
|
||||
</tr>
|
||||
</table>
|
||||
</td>
|
||||
|
@ -5584,10 +5640,196 @@ div.greydiv { vertical-align:top ; text-align:center ; background:#eeeeee ; bord
|
|||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
<a name="module_uart_0"> </a>
|
||||
<div>
|
||||
<hr/>
|
||||
<h2>uart_0</h2>altera_avalon_uart v16.1
|
||||
<br/>
|
||||
<div class="greydiv">
|
||||
<table class="connectionboxes">
|
||||
<tr>
|
||||
<td class="neighbor" rowspan="6">
|
||||
<a href="#module_nios2_gen2">nios2_gen2</a>
|
||||
</td>
|
||||
<td class="from">data_master  </td>
|
||||
<td class="main" rowspan="11">uart_0</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  s1</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="from">irq  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  irq</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="from">debug_reset_request  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  reset</td>
|
||||
</tr>
|
||||
<tr style="height:6px">
|
||||
<td></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="neighbor" rowspan="4">
|
||||
<a href="#module_clk_50">clk_50</a>
|
||||
</td>
|
||||
<td class="from">clk  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  clk</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="from">clk_reset  </td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="to">  reset</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
<br/>
|
||||
<br/>
|
||||
<table class="flowbox">
|
||||
<tr>
|
||||
<td class="parametersbox">
|
||||
<h2>Parameters</h2>
|
||||
<table>
|
||||
<tr>
|
||||
<td class="parametername">baud</td>
|
||||
<td class="parametervalue">115200</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">dataBits</td>
|
||||
<td class="parametervalue">8</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">fixedBaud</td>
|
||||
<td class="parametervalue">true</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">parity</td>
|
||||
<td class="parametervalue">NONE</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">simCharStream</td>
|
||||
<td class="parametervalue"></td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">simInteractiveInputEnable</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">simInteractiveOutputEnable</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">simTrueBaud</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">stopBits</td>
|
||||
<td class="parametervalue">1</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">syncRegDepth</td>
|
||||
<td class="parametervalue">2</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">useCtsRts</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">useEopRegister</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">useRelativePathForSimFile</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">clockRate</td>
|
||||
<td class="parametervalue">50000000</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">baudError</td>
|
||||
<td class="parametervalue">0.01</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">parityFisrtChar</td>
|
||||
<td class="parametervalue">N</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">deviceFamily</td>
|
||||
<td class="parametervalue">UNKNOWN</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">generateLegacySim</td>
|
||||
<td class="parametervalue">false</td>
|
||||
</tr>
|
||||
</table>
|
||||
</td>
|
||||
</tr>
|
||||
</table>  
|
||||
<table class="flowbox">
|
||||
<tr>
|
||||
<td class="parametersbox">
|
||||
<h2>Software Assignments</h2>
|
||||
<table>
|
||||
<tr>
|
||||
<td class="parametername">BAUD</td>
|
||||
<td class="parametervalue">115200</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">DATA_BITS</td>
|
||||
<td class="parametervalue">8</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">FIXED_BAUD</td>
|
||||
<td class="parametervalue">1</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">FREQ</td>
|
||||
<td class="parametervalue">50000000</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">PARITY</td>
|
||||
<td class="parametervalue">'N'</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">SIM_CHAR_STREAM</td>
|
||||
<td class="parametervalue">""</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">SIM_TRUE_BAUD</td>
|
||||
<td class="parametervalue">0</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">STOP_BITS</td>
|
||||
<td class="parametervalue">1</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">SYNC_REG_DEPTH</td>
|
||||
<td class="parametervalue">2</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">USE_CTS_RTS</td>
|
||||
<td class="parametervalue">0</td>
|
||||
</tr>
|
||||
<tr>
|
||||
<td class="parametername">USE_EOP_REGISTER</td>
|
||||
<td class="parametervalue">0</td>
|
||||
</tr>
|
||||
</table>
|
||||
</td>
|
||||
</tr>
|
||||
</table>
|
||||
</div>
|
||||
<table class="blueBar">
|
||||
<tr>
|
||||
<td class="l">generation took 0.01 seconds</td>
|
||||
<td class="r">rendering took 0.08 seconds</td>
|
||||
<td class="l">generation took 0.00 seconds</td>
|
||||
<td class="r">rendering took 0.03 seconds</td>
|
||||
</tr>
|
||||
</table>
|
||||
</body>
|
||||
|
|
File diff suppressed because one or more lines are too long
|
@ -41,7 +41,9 @@ module Qsys (
|
|||
terasic_camera_0_conduit_end_D,
|
||||
terasic_camera_0_conduit_end_FVAL,
|
||||
terasic_camera_0_conduit_end_LVAL,
|
||||
terasic_camera_0_conduit_end_PIXCLK);
|
||||
terasic_camera_0_conduit_end_PIXCLK,
|
||||
uart_0_rx_tx_rxd,
|
||||
uart_0_rx_tx_txd);
|
||||
|
||||
input alt_vip_itc_0_clocked_video_vid_clk;
|
||||
output [23:0] alt_vip_itc_0_clocked_video_vid_data;
|
||||
|
@ -85,4 +87,6 @@ module Qsys (
|
|||
input terasic_camera_0_conduit_end_FVAL;
|
||||
input terasic_camera_0_conduit_end_LVAL;
|
||||
input terasic_camera_0_conduit_end_PIXCLK;
|
||||
input uart_0_rx_tx_rxd;
|
||||
output uart_0_rx_tx_txd;
|
||||
endmodule
|
||||
|
|
|
@ -1,9 +1,7 @@
|
|||
Info: Starting: Create block symbol file (.bsf)
|
||||
Info: qsys-generate "C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys.qsys" --block-symbol-file --output-directory="C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys" --family="MAX 10" --part=10M50DAF484C7G
|
||||
Info: qsys-generate /home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys.qsys --block-symbol-file --output-directory=/home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys --family="MAX 10" --part=10M50DAF484C7G
|
||||
Progress: Loading DE10_LITE_D8M_VIP_16/Qsys.qsys
|
||||
Progress: Reading input file
|
||||
Progress: Adding EEE_IMGPROC_0 [EEE_IMGPROC 1.0]
|
||||
Progress: Parameterizing module EEE_IMGPROC_0
|
||||
Progress: Adding TERASIC_AUTO_FOCUS_0 [TERASIC_AUTO_FOCUS 1.0]
|
||||
Progress: Parameterizing module TERASIC_AUTO_FOCUS_0
|
||||
Progress: Adding TERASIC_CAMERA_0 [TERASIC_CAMERA 1.0]
|
||||
|
@ -12,35 +10,35 @@ Progress: Adding alt_vip_itc_0 [alt_vip_itc 14.0]
|
|||
Progress: Parameterizing module alt_vip_itc_0
|
||||
Progress: Adding alt_vip_vfb_0 [alt_vip_vfb 13.1]
|
||||
Progress: Parameterizing module alt_vip_vfb_0
|
||||
Progress: Adding altpll_0 [altpll 16.1]
|
||||
Progress: Adding altpll_0 [altpll 16.0]
|
||||
Progress: Parameterizing module altpll_0
|
||||
Progress: Adding clk_50 [clock_source 16.1]
|
||||
Progress: Adding clk_50 [clock_source 16.0]
|
||||
Progress: Parameterizing module clk_50
|
||||
Progress: Adding i2c_opencores_camera [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_camera
|
||||
Progress: Adding i2c_opencores_mipi [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_mipi
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.1]
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.0]
|
||||
Progress: Parameterizing module jtag_uart
|
||||
Progress: Adding key [altera_avalon_pio 16.1]
|
||||
Progress: Adding key [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module key
|
||||
Progress: Adding led [altera_avalon_pio 16.1]
|
||||
Progress: Adding led [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module led
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_pwdn_n
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_reset_n
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.1]
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.0]
|
||||
Progress: Parameterizing module nios2_gen2
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.1]
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.0]
|
||||
Progress: Parameterizing module onchip_memory2_0
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.1]
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.0]
|
||||
Progress: Parameterizing module sdram
|
||||
Progress: Adding sw [altera_avalon_pio 16.1]
|
||||
Progress: Adding sw [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module sw
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.1]
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.0]
|
||||
Progress: Parameterizing module sysid_qsys
|
||||
Progress: Adding timer [altera_avalon_timer 16.1]
|
||||
Progress: Adding timer [altera_avalon_timer 16.0]
|
||||
Progress: Parameterizing module timer
|
||||
Progress: Building connections
|
||||
Progress: Parameterizing connections
|
||||
|
@ -49,7 +47,6 @@ Progress: Done reading input file
|
|||
Info: Qsys.alt_vip_vfb_0: The Frame Buffer will no longer be available after 16.1, please upgrade to Frame Buffer II.
|
||||
Info: Qsys.jtag_uart: JTAG UART IP input clock need to be at least double (2x) the operating frequency of JTAG TCK on board
|
||||
Info: Qsys.key: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sdram: SDRAM Controller will only be supported in Quartus Prime Standard Edition in the future release.
|
||||
Info: Qsys.sw: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sysid_qsys: System ID is not assigned automatically. Edit the System ID parameter to provide a unique ID
|
||||
Info: Qsys.sysid_qsys: Time stamp will be automatically updated when this component is generated.
|
||||
|
@ -57,11 +54,9 @@ Info: qsys-generate succeeded.
|
|||
Info: Finished: Create block symbol file (.bsf)
|
||||
Info:
|
||||
Info: Starting: Create HDL design files for synthesis
|
||||
Info: qsys-generate "C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys.qsys" --synthesis=VERILOG --output-directory="C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys\synthesis" --family="MAX 10" --part=10M50DAF484C7G
|
||||
Info: qsys-generate /home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys.qsys --synthesis=VERILOG --output-directory=/home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys/synthesis --family="MAX 10" --part=10M50DAF484C7G
|
||||
Progress: Loading DE10_LITE_D8M_VIP_16/Qsys.qsys
|
||||
Progress: Reading input file
|
||||
Progress: Adding EEE_IMGPROC_0 [EEE_IMGPROC 1.0]
|
||||
Progress: Parameterizing module EEE_IMGPROC_0
|
||||
Progress: Adding TERASIC_AUTO_FOCUS_0 [TERASIC_AUTO_FOCUS 1.0]
|
||||
Progress: Parameterizing module TERASIC_AUTO_FOCUS_0
|
||||
Progress: Adding TERASIC_CAMERA_0 [TERASIC_CAMERA 1.0]
|
||||
|
@ -70,35 +65,35 @@ Progress: Adding alt_vip_itc_0 [alt_vip_itc 14.0]
|
|||
Progress: Parameterizing module alt_vip_itc_0
|
||||
Progress: Adding alt_vip_vfb_0 [alt_vip_vfb 13.1]
|
||||
Progress: Parameterizing module alt_vip_vfb_0
|
||||
Progress: Adding altpll_0 [altpll 16.1]
|
||||
Progress: Adding altpll_0 [altpll 16.0]
|
||||
Progress: Parameterizing module altpll_0
|
||||
Progress: Adding clk_50 [clock_source 16.1]
|
||||
Progress: Adding clk_50 [clock_source 16.0]
|
||||
Progress: Parameterizing module clk_50
|
||||
Progress: Adding i2c_opencores_camera [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_camera
|
||||
Progress: Adding i2c_opencores_mipi [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_mipi
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.1]
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.0]
|
||||
Progress: Parameterizing module jtag_uart
|
||||
Progress: Adding key [altera_avalon_pio 16.1]
|
||||
Progress: Adding key [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module key
|
||||
Progress: Adding led [altera_avalon_pio 16.1]
|
||||
Progress: Adding led [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module led
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_pwdn_n
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_reset_n
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.1]
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.0]
|
||||
Progress: Parameterizing module nios2_gen2
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.1]
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.0]
|
||||
Progress: Parameterizing module onchip_memory2_0
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.1]
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.0]
|
||||
Progress: Parameterizing module sdram
|
||||
Progress: Adding sw [altera_avalon_pio 16.1]
|
||||
Progress: Adding sw [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module sw
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.1]
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.0]
|
||||
Progress: Parameterizing module sysid_qsys
|
||||
Progress: Adding timer [altera_avalon_timer 16.1]
|
||||
Progress: Adding timer [altera_avalon_timer 16.0]
|
||||
Progress: Parameterizing module timer
|
||||
Progress: Building connections
|
||||
Progress: Parameterizing connections
|
||||
|
@ -107,167 +102,28 @@ Progress: Done reading input file
|
|||
Info: Qsys.alt_vip_vfb_0: The Frame Buffer will no longer be available after 16.1, please upgrade to Frame Buffer II.
|
||||
Info: Qsys.jtag_uart: JTAG UART IP input clock need to be at least double (2x) the operating frequency of JTAG TCK on board
|
||||
Info: Qsys.key: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sdram: SDRAM Controller will only be supported in Quartus Prime Standard Edition in the future release.
|
||||
Info: Qsys.sw: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sysid_qsys: System ID is not assigned automatically. Edit the System ID parameter to provide a unique ID
|
||||
Info: Qsys.sysid_qsys: Time stamp will be automatically updated when this component is generated.
|
||||
Info: Qsys: Generating Qsys "Qsys" for QUARTUS_SYNTH
|
||||
Info: Inserting clock-crossing logic between cmd_demux.src5 and cmd_mux_005.sink0
|
||||
Info: Inserting clock-crossing logic between cmd_demux.src14 and cmd_mux_014.sink0
|
||||
Info: Inserting clock-crossing logic between rsp_demux_005.src0 and rsp_mux.sink5
|
||||
Info: Inserting clock-crossing logic between rsp_demux_014.src0 and rsp_mux.sink14
|
||||
Info: EEE_IMGPROC_0: "Qsys" instantiated EEE_IMGPROC "EEE_IMGPROC_0"
|
||||
Info: TERASIC_AUTO_FOCUS_0: "Qsys" instantiated TERASIC_AUTO_FOCUS "TERASIC_AUTO_FOCUS_0"
|
||||
Info: TERASIC_CAMERA_0: "Qsys" instantiated TERASIC_CAMERA "TERASIC_CAMERA_0"
|
||||
Info: alt_vip_itc_0: "Qsys" instantiated alt_vip_itc "alt_vip_itc_0"
|
||||
Info: alt_vip_vfb_0: "Qsys" instantiated alt_vip_vfb "alt_vip_vfb_0"
|
||||
Info: altpll_0: Error while generating Qsys_altpll_0.v : 1 : Illegal port or parameter name scandone Illegal port or parameter name scanclkena Illegal port or parameter name scandataout Illegal port or parameter name configupdate Illegal port or parameter name scandata child process exited abnormally
|
||||
Info: altpll_0: Illegal port or parameter name scandone Illegal port or parameter name scanclkena Illegal port or parameter name scandataout Illegal port or parameter name configupdate Illegal port or parameter name scandata child process exited abnormally while executing "exec /home/ed/altera_lite/16.0/quartus/linux64/clearbox altpll_avalon device_family=MAX10 CBX_FILE=Qsys_altpll_0.v -f cbxcmdln_1617092322619640" ("eval" body line 1) invoked from within "eval exec $cbx_cmd "
|
||||
Error: Can't continue processing -- expected file /tmp/alt8716_2763057626446894966.dir/0017_sopcgen/Qsys_altpll_0.v is missing
|
||||
Warning: Quartus Prime Generate HDL Interface was unsuccessful. 1 error, 0 warnings
|
||||
Error: Peak virtual memory: 1399 megabytes
|
||||
Error: Processing ended: Tue Mar 30 09:18:43 2021
|
||||
Error: Elapsed time: 00:00:01
|
||||
Error: Total CPU time (on all processors): 00:00:00
|
||||
Error: altpll_0: File /tmp/alt8716_2763057626446894966.dir/0017_sopcgen/Qsys_altpll_0.v written by generation callback did not contain a module called Qsys_altpll_0
|
||||
Error: altpll_0: /tmp/alt8716_2763057626446894966.dir/0017_sopcgen/Qsys_altpll_0.v (No such file or directory)
|
||||
Info: altpll_0: "Qsys" instantiated altpll "altpll_0"
|
||||
Info: i2c_opencores_camera: "Qsys" instantiated i2c_opencores "i2c_opencores_camera"
|
||||
Info: jtag_uart: Starting RTL generation for module 'Qsys_jtag_uart'
|
||||
Info: jtag_uart: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_jtag_uart -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_jtag_uart/generate_rtl.pl --name=Qsys_jtag_uart --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0011_jtag_uart_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0011_jtag_uart_gen//Qsys_jtag_uart_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: jtag_uart: Done RTL generation for module 'Qsys_jtag_uart'
|
||||
Info: jtag_uart: "Qsys" instantiated altera_avalon_jtag_uart "jtag_uart"
|
||||
Info: key: Starting RTL generation for module 'Qsys_key'
|
||||
Info: key: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_key --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0012_key_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0012_key_gen//Qsys_key_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: key: Done RTL generation for module 'Qsys_key'
|
||||
Info: key: "Qsys" instantiated altera_avalon_pio "key"
|
||||
Info: led: Starting RTL generation for module 'Qsys_led'
|
||||
Info: led: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_led --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0013_led_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0013_led_gen//Qsys_led_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: led: Done RTL generation for module 'Qsys_led'
|
||||
Info: led: "Qsys" instantiated altera_avalon_pio "led"
|
||||
Info: mipi_pwdn_n: Starting RTL generation for module 'Qsys_mipi_pwdn_n'
|
||||
Info: mipi_pwdn_n: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_mipi_pwdn_n --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0014_mipi_pwdn_n_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0014_mipi_pwdn_n_gen//Qsys_mipi_pwdn_n_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: mipi_pwdn_n: Done RTL generation for module 'Qsys_mipi_pwdn_n'
|
||||
Info: mipi_pwdn_n: "Qsys" instantiated altera_avalon_pio "mipi_pwdn_n"
|
||||
Info: nios2_gen2: "Qsys" instantiated altera_nios2_gen2 "nios2_gen2"
|
||||
Info: onchip_memory2_0: Starting RTL generation for module 'Qsys_onchip_memory2_0'
|
||||
Info: onchip_memory2_0: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_onchip_memory2 -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_onchip_memory2/generate_rtl.pl --name=Qsys_onchip_memory2_0 --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0015_onchip_memory2_0_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0015_onchip_memory2_0_gen//Qsys_onchip_memory2_0_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: onchip_memory2_0: Done RTL generation for module 'Qsys_onchip_memory2_0'
|
||||
Info: onchip_memory2_0: "Qsys" instantiated altera_avalon_onchip_memory2 "onchip_memory2_0"
|
||||
Info: sdram: Starting RTL generation for module 'Qsys_sdram'
|
||||
Info: sdram: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_new_sdram_controller -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_new_sdram_controller/generate_rtl.pl --name=Qsys_sdram --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0016_sdram_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0016_sdram_gen//Qsys_sdram_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: sdram: Done RTL generation for module 'Qsys_sdram'
|
||||
Info: sdram: "Qsys" instantiated altera_avalon_new_sdram_controller "sdram"
|
||||
Info: sw: Starting RTL generation for module 'Qsys_sw'
|
||||
Info: sw: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_sw --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0017_sw_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0017_sw_gen//Qsys_sw_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: sw: Done RTL generation for module 'Qsys_sw'
|
||||
Info: sw: "Qsys" instantiated altera_avalon_pio "sw"
|
||||
Info: sysid_qsys: "Qsys" instantiated altera_avalon_sysid_qsys "sysid_qsys"
|
||||
Info: timer: Starting RTL generation for module 'Qsys_timer'
|
||||
Info: timer: Generation command is [exec C:/intelFPGA_lite/16.1/quartus/bin64//perl/bin/perl.exe -I C:/intelFPGA_lite/16.1/quartus/bin64//perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_timer -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_timer/generate_rtl.pl --name=Qsys_timer --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0019_timer_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0019_timer_gen//Qsys_timer_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: timer: Done RTL generation for module 'Qsys_timer'
|
||||
Info: timer: "Qsys" instantiated altera_avalon_timer "timer"
|
||||
Info: avalon_st_adapter: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_001: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_002: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_003: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_004: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_005: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_006: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_007: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_008: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_009: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_010: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_011: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_012: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_013: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_014: Inserting error_adapter: error_adapter_0
|
||||
Info: mm_interconnect_0: "Qsys" instantiated altera_mm_interconnect "mm_interconnect_0"
|
||||
Info: avalon_st_adapter: Inserting error_adapter: error_adapter_0
|
||||
Info: mm_interconnect_1: "Qsys" instantiated altera_mm_interconnect "mm_interconnect_1"
|
||||
Info: irq_mapper: "Qsys" instantiated altera_irq_mapper "irq_mapper"
|
||||
Info: rst_controller: "Qsys" instantiated altera_reset_controller "rst_controller"
|
||||
Info: vfb_writer_packet_write_address_au_l_muxinst: "alt_vip_vfb_0" instantiated alt_cusp_muxbin2 "vfb_writer_packet_write_address_au_l_muxinst"
|
||||
Info: vfb_writer_packet_write_address_au: "alt_vip_vfb_0" instantiated alt_au "vfb_writer_packet_write_address_au"
|
||||
Info: vfb_writer_overflow_flag_reg: "alt_vip_vfb_0" instantiated alt_reg "vfb_writer_overflow_flag_reg"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: vfb_writer_length_counter_au_enable_muxinst: "alt_vip_vfb_0" instantiated alt_cusp_muxhot16 "vfb_writer_length_counter_au_enable_muxinst"
|
||||
Info: din: "alt_vip_vfb_0" instantiated alt_avalon_st_input "din"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: dout: "alt_vip_vfb_0" instantiated alt_avalon_st_output "dout"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: read_master: "alt_vip_vfb_0" instantiated alt_avalon_mm_bursting_master_fifo "read_master"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: read_master_pull: "alt_vip_vfb_0" instantiated alt_cusp_pulling_width_adapter "read_master_pull"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: write_master_push: "alt_vip_vfb_0" instantiated alt_cusp_pushing_width_adapter "write_master_push"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: pc0: "alt_vip_vfb_0" instantiated alt_pc "pc0"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: fu_id_4494_line325_93: "alt_vip_vfb_0" instantiated alt_cmp "fu_id_4494_line325_93"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: clocksource: "alt_vip_vfb_0" instantiated alt_cusp_testbench_clock "clocksource"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: cpu: Starting RTL generation for module 'Qsys_nios2_gen2_cpu'
|
||||
Info: cpu: Generation command is [exec C:/intelFPGA_lite/16.1/quartus/bin64//eperlcmd.exe -I C:/intelFPGA_lite/16.1/quartus/bin64//perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/cpu_lib -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/nios_lib -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2 -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2 -- C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/generate_rtl.epl --name=Qsys_nios2_gen2_cpu --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0022_cpu_gen/ --quartus_bindir=C:/intelFPGA_lite/16.1/quartus/bin64/ --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_3370923321813107178.dir/0022_cpu_gen//Qsys_nios2_gen2_cpu_processor_configuration.pl --do_build_sim=0 ]
|
||||
Info: cpu: # 2021.05.27 17:51:00 (*) Starting Nios II generation
|
||||
Info: cpu: # 2021.05.27 17:51:00 (*) Checking for plaintext license.
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Couldn't query license setup in Quartus directory C:/intelFPGA_lite/16.1/quartus/bin64/
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Defaulting to contents of LM_LICENSE_FILE environment variable
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) LM_LICENSE_FILE environment variable is empty
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Plaintext license not found.
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Checking for encrypted license (non-evaluation).
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Couldn't query license setup in Quartus directory C:/intelFPGA_lite/16.1/quartus/bin64/
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Defaulting to contents of LM_LICENSE_FILE environment variable
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) LM_LICENSE_FILE environment variable is empty
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Encrypted license not found. Defaulting to OCP evaluation license (produces a time-limited SOF)
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Elaborating CPU configuration settings
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Creating all objects for CPU
|
||||
Info: cpu: # 2021.05.27 17:51:01 (*) Testbench
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Instruction decoding
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Instruction fields
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Instruction decodes
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Signals for RTL simulation waveforms
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Instruction controls
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Pipeline frontend
|
||||
Info: cpu: # 2021.05.27 17:51:02 (*) Pipeline backend
|
||||
Info: cpu: # 2021.05.27 17:51:05 (*) Generating RTL from CPU objects
|
||||
Info: cpu: # 2021.05.27 17:51:06 (*) Creating encrypted RTL
|
||||
Info: cpu: # 2021.05.27 17:51:07 (*) Done Nios II generation
|
||||
Info: cpu: Done RTL generation for module 'Qsys_nios2_gen2_cpu'
|
||||
Info: cpu: "nios2_gen2" instantiated altera_nios2_gen2_unit "cpu"
|
||||
Info: nios2_gen2_data_master_translator: "mm_interconnect_0" instantiated altera_merlin_master_translator "nios2_gen2_data_master_translator"
|
||||
Info: jtag_uart_avalon_jtag_slave_translator: "mm_interconnect_0" instantiated altera_merlin_slave_translator "jtag_uart_avalon_jtag_slave_translator"
|
||||
Info: nios2_gen2_data_master_agent: "mm_interconnect_0" instantiated altera_merlin_master_agent "nios2_gen2_data_master_agent"
|
||||
Info: jtag_uart_avalon_jtag_slave_agent: "mm_interconnect_0" instantiated altera_merlin_slave_agent "jtag_uart_avalon_jtag_slave_agent"
|
||||
Info: jtag_uart_avalon_jtag_slave_agent_rsp_fifo: "mm_interconnect_0" instantiated altera_avalon_sc_fifo "jtag_uart_avalon_jtag_slave_agent_rsp_fifo"
|
||||
Info: router: "mm_interconnect_0" instantiated altera_merlin_router "router"
|
||||
Info: router_001: "mm_interconnect_0" instantiated altera_merlin_router "router_001"
|
||||
Info: router_002: "mm_interconnect_0" instantiated altera_merlin_router "router_002"
|
||||
Info: router_006: "mm_interconnect_0" instantiated altera_merlin_router "router_006"
|
||||
Info: nios2_gen2_data_master_limiter: "mm_interconnect_0" instantiated altera_merlin_traffic_limiter "nios2_gen2_data_master_limiter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_sc_fifo.v
|
||||
Info: cmd_demux: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "cmd_demux"
|
||||
Info: cmd_demux_001: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "cmd_demux_001"
|
||||
Info: cmd_mux: "mm_interconnect_0" instantiated altera_merlin_multiplexer "cmd_mux"
|
||||
Info: cmd_mux_004: "mm_interconnect_0" instantiated altera_merlin_multiplexer "cmd_mux_004"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_demux: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux"
|
||||
Info: rsp_demux_004: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux_004"
|
||||
Info: rsp_demux_005: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux_005"
|
||||
Info: rsp_mux: "mm_interconnect_0" instantiated altera_merlin_multiplexer "rsp_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_mux_001: "mm_interconnect_0" instantiated altera_merlin_multiplexer "rsp_mux_001"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: crosser: "mm_interconnect_0" instantiated altera_avalon_st_handshake_clock_crosser "crosser"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_st_pipeline_base.v
|
||||
Info: avalon_st_adapter: "mm_interconnect_0" instantiated altera_avalon_st_adapter "avalon_st_adapter"
|
||||
Info: router: "mm_interconnect_1" instantiated altera_merlin_router "router"
|
||||
Info: router_002: "mm_interconnect_1" instantiated altera_merlin_router "router_002"
|
||||
Info: sdram_s1_burst_adapter: "mm_interconnect_1" instantiated altera_merlin_burst_adapter "sdram_s1_burst_adapter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_st_pipeline_base.v
|
||||
Info: cmd_demux: "mm_interconnect_1" instantiated altera_merlin_demultiplexer "cmd_demux"
|
||||
Info: cmd_mux: "mm_interconnect_1" instantiated altera_merlin_multiplexer "cmd_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_demux: "mm_interconnect_1" instantiated altera_merlin_demultiplexer "rsp_demux"
|
||||
Info: rsp_mux: "mm_interconnect_1" instantiated altera_merlin_multiplexer "rsp_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: sdram_s1_rsp_width_adapter: "mm_interconnect_1" instantiated altera_merlin_width_adapter "sdram_s1_rsp_width_adapter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_address_alignment.sv
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_burst_uncompressor.sv
|
||||
Info: avalon_st_adapter: "mm_interconnect_1" instantiated altera_avalon_st_adapter "avalon_st_adapter"
|
||||
Info: error_adapter_0: "avalon_st_adapter" instantiated error_adapter "error_adapter_0"
|
||||
Info: error_adapter_0: "avalon_st_adapter" instantiated error_adapter "error_adapter_0"
|
||||
Info: Qsys: Done "Qsys" with 67 modules, 142 files
|
||||
Info: qsys-generate succeeded.
|
||||
Error: Generation stopped, 218 or more modules remaining
|
||||
Info: Qsys: Done "Qsys" with 33 modules, 34 files
|
||||
Error: qsys-generate failed with exit code 1: 8 Errors, 1 Warning
|
||||
Info: Finished: Create HDL design files for synthesis
|
||||
|
|
|
@ -1,9 +1,7 @@
|
|||
Info: Starting: Create block symbol file (.bsf)
|
||||
Info: qsys-generate "C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys.qsys" --block-symbol-file --output-directory="C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys" --family="MAX 10" --part=10M50DAF484C7G
|
||||
Info: qsys-generate /home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys.qsys --block-symbol-file --output-directory=/home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys --family="MAX 10" --part=10M50DAF484C7G
|
||||
Progress: Loading DE10_LITE_D8M_VIP_16/Qsys.qsys
|
||||
Progress: Reading input file
|
||||
Progress: Adding EEE_IMGPROC_0 [EEE_IMGPROC 1.0]
|
||||
Progress: Parameterizing module EEE_IMGPROC_0
|
||||
Progress: Adding TERASIC_AUTO_FOCUS_0 [TERASIC_AUTO_FOCUS 1.0]
|
||||
Progress: Parameterizing module TERASIC_AUTO_FOCUS_0
|
||||
Progress: Adding TERASIC_CAMERA_0 [TERASIC_CAMERA 1.0]
|
||||
|
@ -12,38 +10,36 @@ Progress: Adding alt_vip_itc_0 [alt_vip_itc 14.0]
|
|||
Progress: Parameterizing module alt_vip_itc_0
|
||||
Progress: Adding alt_vip_vfb_0 [alt_vip_vfb 13.1]
|
||||
Progress: Parameterizing module alt_vip_vfb_0
|
||||
Progress: Adding altpll_0 [altpll 16.1]
|
||||
Progress: Adding altpll_0 [altpll 16.0]
|
||||
Progress: Parameterizing module altpll_0
|
||||
Progress: Adding clk_50 [clock_source 16.1]
|
||||
Progress: Adding clk_50 [clock_source 16.0]
|
||||
Progress: Parameterizing module clk_50
|
||||
Progress: Adding i2c_opencores_camera [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_camera
|
||||
Progress: Adding i2c_opencores_mipi [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_mipi
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.1]
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.0]
|
||||
Progress: Parameterizing module jtag_uart
|
||||
Progress: Adding key [altera_avalon_pio 16.1]
|
||||
Progress: Adding key [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module key
|
||||
Progress: Adding led [altera_avalon_pio 16.1]
|
||||
Progress: Adding led [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module led
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_pwdn_n
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_reset_n
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.1]
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.0]
|
||||
Progress: Parameterizing module nios2_gen2
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.1]
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.0]
|
||||
Progress: Parameterizing module onchip_memory2_0
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.1]
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.0]
|
||||
Progress: Parameterizing module sdram
|
||||
Progress: Adding sw [altera_avalon_pio 16.1]
|
||||
Progress: Adding sw [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module sw
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.1]
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.0]
|
||||
Progress: Parameterizing module sysid_qsys
|
||||
Progress: Adding timer [altera_avalon_timer 16.1]
|
||||
Progress: Adding timer [altera_avalon_timer 16.0]
|
||||
Progress: Parameterizing module timer
|
||||
Progress: Adding uart_interface_0 [uart_interface 1.0]
|
||||
Progress: Parameterizing module uart_interface_0
|
||||
Progress: Building connections
|
||||
Progress: Parameterizing connections
|
||||
Progress: Validating
|
||||
|
@ -51,7 +47,6 @@ Progress: Done reading input file
|
|||
Info: Qsys.alt_vip_vfb_0: The Frame Buffer will no longer be available after 16.1, please upgrade to Frame Buffer II.
|
||||
Info: Qsys.jtag_uart: JTAG UART IP input clock need to be at least double (2x) the operating frequency of JTAG TCK on board
|
||||
Info: Qsys.key: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sdram: SDRAM Controller will only be supported in Quartus Prime Standard Edition in the future release.
|
||||
Info: Qsys.sw: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sysid_qsys: System ID is not assigned automatically. Edit the System ID parameter to provide a unique ID
|
||||
Info: Qsys.sysid_qsys: Time stamp will be automatically updated when this component is generated.
|
||||
|
@ -59,11 +54,9 @@ Info: qsys-generate succeeded.
|
|||
Info: Finished: Create block symbol file (.bsf)
|
||||
Info:
|
||||
Info: Starting: Create HDL design files for synthesis
|
||||
Info: qsys-generate "C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys.qsys" --synthesis=VERILOG --output-directory="C:\Users\Anish Ghanekar\OneDrive - Imperial College London\GitHub\EE2Rover\Vision\DE10_LITE_D8M_VIP_16\Qsys\synthesis" --family="MAX 10" --part=10M50DAF484C7G
|
||||
Info: qsys-generate /home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys.qsys --synthesis=VERILOG --output-directory=/home/ed/stuff/EEE2Rover/DE10_LITE_D8M_VIP_16/Qsys/synthesis --family="MAX 10" --part=10M50DAF484C7G
|
||||
Progress: Loading DE10_LITE_D8M_VIP_16/Qsys.qsys
|
||||
Progress: Reading input file
|
||||
Progress: Adding EEE_IMGPROC_0 [EEE_IMGPROC 1.0]
|
||||
Progress: Parameterizing module EEE_IMGPROC_0
|
||||
Progress: Adding TERASIC_AUTO_FOCUS_0 [TERASIC_AUTO_FOCUS 1.0]
|
||||
Progress: Parameterizing module TERASIC_AUTO_FOCUS_0
|
||||
Progress: Adding TERASIC_CAMERA_0 [TERASIC_CAMERA 1.0]
|
||||
|
@ -72,38 +65,36 @@ Progress: Adding alt_vip_itc_0 [alt_vip_itc 14.0]
|
|||
Progress: Parameterizing module alt_vip_itc_0
|
||||
Progress: Adding alt_vip_vfb_0 [alt_vip_vfb 13.1]
|
||||
Progress: Parameterizing module alt_vip_vfb_0
|
||||
Progress: Adding altpll_0 [altpll 16.1]
|
||||
Progress: Adding altpll_0 [altpll 16.0]
|
||||
Progress: Parameterizing module altpll_0
|
||||
Progress: Adding clk_50 [clock_source 16.1]
|
||||
Progress: Adding clk_50 [clock_source 16.0]
|
||||
Progress: Parameterizing module clk_50
|
||||
Progress: Adding i2c_opencores_camera [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_camera
|
||||
Progress: Adding i2c_opencores_mipi [i2c_opencores 12.0]
|
||||
Progress: Parameterizing module i2c_opencores_mipi
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.1]
|
||||
Progress: Adding jtag_uart [altera_avalon_jtag_uart 16.0]
|
||||
Progress: Parameterizing module jtag_uart
|
||||
Progress: Adding key [altera_avalon_pio 16.1]
|
||||
Progress: Adding key [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module key
|
||||
Progress: Adding led [altera_avalon_pio 16.1]
|
||||
Progress: Adding led [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module led
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_pwdn_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_pwdn_n
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.1]
|
||||
Progress: Adding mipi_reset_n [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module mipi_reset_n
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.1]
|
||||
Progress: Adding nios2_gen2 [altera_nios2_gen2 16.0]
|
||||
Progress: Parameterizing module nios2_gen2
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.1]
|
||||
Progress: Adding onchip_memory2_0 [altera_avalon_onchip_memory2 16.0]
|
||||
Progress: Parameterizing module onchip_memory2_0
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.1]
|
||||
Progress: Adding sdram [altera_avalon_new_sdram_controller 16.0]
|
||||
Progress: Parameterizing module sdram
|
||||
Progress: Adding sw [altera_avalon_pio 16.1]
|
||||
Progress: Adding sw [altera_avalon_pio 16.0]
|
||||
Progress: Parameterizing module sw
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.1]
|
||||
Progress: Adding sysid_qsys [altera_avalon_sysid_qsys 16.0]
|
||||
Progress: Parameterizing module sysid_qsys
|
||||
Progress: Adding timer [altera_avalon_timer 16.1]
|
||||
Progress: Adding timer [altera_avalon_timer 16.0]
|
||||
Progress: Parameterizing module timer
|
||||
Progress: Adding uart_interface_0 [uart_interface 1.0]
|
||||
Progress: Parameterizing module uart_interface_0
|
||||
Progress: Building connections
|
||||
Progress: Parameterizing connections
|
||||
Progress: Validating
|
||||
|
@ -111,168 +102,28 @@ Progress: Done reading input file
|
|||
Info: Qsys.alt_vip_vfb_0: The Frame Buffer will no longer be available after 16.1, please upgrade to Frame Buffer II.
|
||||
Info: Qsys.jtag_uart: JTAG UART IP input clock need to be at least double (2x) the operating frequency of JTAG TCK on board
|
||||
Info: Qsys.key: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sdram: SDRAM Controller will only be supported in Quartus Prime Standard Edition in the future release.
|
||||
Info: Qsys.sw: PIO inputs are not hardwired in test bench. Undefined values will be read from PIO inputs during simulation.
|
||||
Info: Qsys.sysid_qsys: System ID is not assigned automatically. Edit the System ID parameter to provide a unique ID
|
||||
Info: Qsys.sysid_qsys: Time stamp will be automatically updated when this component is generated.
|
||||
Info: Qsys: Generating Qsys "Qsys" for QUARTUS_SYNTH
|
||||
Info: Inserting clock-crossing logic between cmd_demux.src5 and cmd_mux_005.sink0
|
||||
Info: Inserting clock-crossing logic between cmd_demux.src14 and cmd_mux_014.sink0
|
||||
Info: Inserting clock-crossing logic between rsp_demux_005.src0 and rsp_mux.sink5
|
||||
Info: Inserting clock-crossing logic between rsp_demux_014.src0 and rsp_mux.sink14
|
||||
Info: EEE_IMGPROC_0: "Qsys" instantiated EEE_IMGPROC "EEE_IMGPROC_0"
|
||||
Info: TERASIC_AUTO_FOCUS_0: "Qsys" instantiated TERASIC_AUTO_FOCUS "TERASIC_AUTO_FOCUS_0"
|
||||
Info: TERASIC_CAMERA_0: "Qsys" instantiated TERASIC_CAMERA "TERASIC_CAMERA_0"
|
||||
Info: alt_vip_itc_0: "Qsys" instantiated alt_vip_itc "alt_vip_itc_0"
|
||||
Info: alt_vip_vfb_0: "Qsys" instantiated alt_vip_vfb "alt_vip_vfb_0"
|
||||
Info: altpll_0: Error while generating Qsys_altpll_0.v : 1 : Illegal port or parameter name scandone Illegal port or parameter name scanclkena Illegal port or parameter name scandataout Illegal port or parameter name configupdate Illegal port or parameter name scandata child process exited abnormally
|
||||
Info: altpll_0: Illegal port or parameter name scandone Illegal port or parameter name scanclkena Illegal port or parameter name scandataout Illegal port or parameter name configupdate Illegal port or parameter name scandata child process exited abnormally while executing "exec /home/ed/altera_lite/16.0/quartus/linux64/clearbox altpll_avalon device_family=MAX10 CBX_FILE=Qsys_altpll_0.v -f cbxcmdln_1617092145442977" ("eval" body line 1) invoked from within "eval exec $cbx_cmd "
|
||||
Error: Can't continue processing -- expected file /tmp/alt8716_2763057626446894966.dir/0014_sopcgen/Qsys_altpll_0.v is missing
|
||||
Warning: Quartus Prime Generate HDL Interface was unsuccessful. 1 error, 0 warnings
|
||||
Error: Peak virtual memory: 1399 megabytes
|
||||
Error: Processing ended: Tue Mar 30 09:15:46 2021
|
||||
Error: Elapsed time: 00:00:00
|
||||
Error: Total CPU time (on all processors): 00:00:00
|
||||
Error: altpll_0: File /tmp/alt8716_2763057626446894966.dir/0014_sopcgen/Qsys_altpll_0.v written by generation callback did not contain a module called Qsys_altpll_0
|
||||
Error: altpll_0: /tmp/alt8716_2763057626446894966.dir/0014_sopcgen/Qsys_altpll_0.v (No such file or directory)
|
||||
Info: altpll_0: "Qsys" instantiated altpll "altpll_0"
|
||||
Info: i2c_opencores_camera: "Qsys" instantiated i2c_opencores "i2c_opencores_camera"
|
||||
Info: jtag_uart: Starting RTL generation for module 'Qsys_jtag_uart'
|
||||
Info: jtag_uart: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_jtag_uart -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_jtag_uart/generate_rtl.pl --name=Qsys_jtag_uart --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0012_jtag_uart_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0012_jtag_uart_gen//Qsys_jtag_uart_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: jtag_uart: Done RTL generation for module 'Qsys_jtag_uart'
|
||||
Info: jtag_uart: "Qsys" instantiated altera_avalon_jtag_uart "jtag_uart"
|
||||
Info: key: Starting RTL generation for module 'Qsys_key'
|
||||
Info: key: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_key --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0013_key_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0013_key_gen//Qsys_key_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: key: Done RTL generation for module 'Qsys_key'
|
||||
Info: key: "Qsys" instantiated altera_avalon_pio "key"
|
||||
Info: led: Starting RTL generation for module 'Qsys_led'
|
||||
Info: led: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_led --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0014_led_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0014_led_gen//Qsys_led_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: led: Done RTL generation for module 'Qsys_led'
|
||||
Info: led: "Qsys" instantiated altera_avalon_pio "led"
|
||||
Info: mipi_pwdn_n: Starting RTL generation for module 'Qsys_mipi_pwdn_n'
|
||||
Info: mipi_pwdn_n: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_mipi_pwdn_n --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0015_mipi_pwdn_n_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0015_mipi_pwdn_n_gen//Qsys_mipi_pwdn_n_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: mipi_pwdn_n: Done RTL generation for module 'Qsys_mipi_pwdn_n'
|
||||
Info: mipi_pwdn_n: "Qsys" instantiated altera_avalon_pio "mipi_pwdn_n"
|
||||
Info: nios2_gen2: "Qsys" instantiated altera_nios2_gen2 "nios2_gen2"
|
||||
Info: onchip_memory2_0: Starting RTL generation for module 'Qsys_onchip_memory2_0'
|
||||
Info: onchip_memory2_0: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_onchip_memory2 -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_onchip_memory2/generate_rtl.pl --name=Qsys_onchip_memory2_0 --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0016_onchip_memory2_0_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0016_onchip_memory2_0_gen//Qsys_onchip_memory2_0_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: onchip_memory2_0: Done RTL generation for module 'Qsys_onchip_memory2_0'
|
||||
Info: onchip_memory2_0: "Qsys" instantiated altera_avalon_onchip_memory2 "onchip_memory2_0"
|
||||
Info: sdram: Starting RTL generation for module 'Qsys_sdram'
|
||||
Info: sdram: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_new_sdram_controller -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_new_sdram_controller/generate_rtl.pl --name=Qsys_sdram --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0017_sdram_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0017_sdram_gen//Qsys_sdram_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: sdram: Done RTL generation for module 'Qsys_sdram'
|
||||
Info: sdram: "Qsys" instantiated altera_avalon_new_sdram_controller "sdram"
|
||||
Info: sw: Starting RTL generation for module 'Qsys_sw'
|
||||
Info: sw: Generation command is [exec C:/intelfpga_lite/16.1/quartus/bin64/perl/bin/perl.exe -I C:/intelfpga_lite/16.1/quartus/bin64/perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_pio/generate_rtl.pl --name=Qsys_sw --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0018_sw_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0018_sw_gen//Qsys_sw_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: sw: Done RTL generation for module 'Qsys_sw'
|
||||
Info: sw: "Qsys" instantiated altera_avalon_pio "sw"
|
||||
Info: sysid_qsys: "Qsys" instantiated altera_avalon_sysid_qsys "sysid_qsys"
|
||||
Info: timer: Starting RTL generation for module 'Qsys_timer'
|
||||
Info: timer: Generation command is [exec C:/intelFPGA_lite/16.1/quartus/bin64//perl/bin/perl.exe -I C:/intelFPGA_lite/16.1/quartus/bin64//perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/common -I C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_timer -- C:/intelfpga_lite/16.1/quartus/../ip/altera/sopc_builder_ip/altera_avalon_timer/generate_rtl.pl --name=Qsys_timer --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0020_timer_gen/ --quartus_dir=C:/intelfpga_lite/16.1/quartus --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0020_timer_gen//Qsys_timer_component_configuration.pl --do_build_sim=0 ]
|
||||
Info: timer: Done RTL generation for module 'Qsys_timer'
|
||||
Info: timer: "Qsys" instantiated altera_avalon_timer "timer"
|
||||
Info: uart_interface_0: "Qsys" instantiated uart_interface "uart_interface_0"
|
||||
Info: avalon_st_adapter: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_001: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_002: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_003: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_004: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_005: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_006: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_007: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_008: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_009: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_010: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_011: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_012: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_013: Inserting error_adapter: error_adapter_0
|
||||
Info: avalon_st_adapter_014: Inserting error_adapter: error_adapter_0
|
||||
Info: mm_interconnect_0: "Qsys" instantiated altera_mm_interconnect "mm_interconnect_0"
|
||||
Info: avalon_st_adapter: Inserting error_adapter: error_adapter_0
|
||||
Info: mm_interconnect_1: "Qsys" instantiated altera_mm_interconnect "mm_interconnect_1"
|
||||
Info: irq_mapper: "Qsys" instantiated altera_irq_mapper "irq_mapper"
|
||||
Info: rst_controller: "Qsys" instantiated altera_reset_controller "rst_controller"
|
||||
Info: vfb_writer_packet_write_address_au_l_muxinst: "alt_vip_vfb_0" instantiated alt_cusp_muxbin2 "vfb_writer_packet_write_address_au_l_muxinst"
|
||||
Info: vfb_writer_packet_write_address_au: "alt_vip_vfb_0" instantiated alt_au "vfb_writer_packet_write_address_au"
|
||||
Info: vfb_writer_overflow_flag_reg: "alt_vip_vfb_0" instantiated alt_reg "vfb_writer_overflow_flag_reg"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: vfb_writer_length_counter_au_enable_muxinst: "alt_vip_vfb_0" instantiated alt_cusp_muxhot16 "vfb_writer_length_counter_au_enable_muxinst"
|
||||
Info: din: "alt_vip_vfb_0" instantiated alt_avalon_st_input "din"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: dout: "alt_vip_vfb_0" instantiated alt_avalon_st_output "dout"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: read_master: "alt_vip_vfb_0" instantiated alt_avalon_mm_bursting_master_fifo "read_master"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: read_master_pull: "alt_vip_vfb_0" instantiated alt_cusp_pulling_width_adapter "read_master_pull"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: write_master_push: "alt_vip_vfb_0" instantiated alt_cusp_pushing_width_adapter "write_master_push"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: pc0: "alt_vip_vfb_0" instantiated alt_pc "pc0"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: fu_id_4494_line325_93: "alt_vip_vfb_0" instantiated alt_cmp "fu_id_4494_line325_93"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: clocksource: "alt_vip_vfb_0" instantiated alt_cusp_testbench_clock "clocksource"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/alt_cusp161_package.vhd
|
||||
Info: cpu: Starting RTL generation for module 'Qsys_nios2_gen2_cpu'
|
||||
Info: cpu: Generation command is [exec C:/intelFPGA_lite/16.1/quartus/bin64//eperlcmd.exe -I C:/intelFPGA_lite/16.1/quartus/bin64//perl/lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/europa -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin/perl_lib -I C:/intelfpga_lite/16.1/quartus/sopc_builder/bin -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/cpu_lib -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/nios_lib -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2 -I C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2 -- C:/intelfpga_lite/16.1/quartus/../ip/altera/nios2_ip/altera_nios2_gen2/generate_rtl.epl --name=Qsys_nios2_gen2_cpu --dir=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0024_cpu_gen/ --quartus_bindir=C:/intelFPGA_lite/16.1/quartus/bin64/ --verilog --config=C:/Users/ANISHG~1/AppData/Local/Temp/alt8774_8656851003626341876.dir/0024_cpu_gen//Qsys_nios2_gen2_cpu_processor_configuration.pl --do_build_sim=0 ]
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Starting Nios II generation
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Checking for plaintext license.
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Couldn't query license setup in Quartus directory C:/intelFPGA_lite/16.1/quartus/bin64/
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Defaulting to contents of LM_LICENSE_FILE environment variable
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) LM_LICENSE_FILE environment variable is empty
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Plaintext license not found.
|
||||
Info: cpu: # 2021.05.27 17:14:55 (*) Checking for encrypted license (non-evaluation).
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Couldn't query license setup in Quartus directory C:/intelFPGA_lite/16.1/quartus/bin64/
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Defaulting to contents of LM_LICENSE_FILE environment variable
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) LM_LICENSE_FILE environment variable is empty
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Encrypted license not found. Defaulting to OCP evaluation license (produces a time-limited SOF)
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Elaborating CPU configuration settings
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Creating all objects for CPU
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Testbench
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Instruction decoding
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Instruction fields
|
||||
Info: cpu: # 2021.05.27 17:14:56 (*) Instruction decodes
|
||||
Info: cpu: # 2021.05.27 17:14:57 (*) Signals for RTL simulation waveforms
|
||||
Info: cpu: # 2021.05.27 17:14:57 (*) Instruction controls
|
||||
Info: cpu: # 2021.05.27 17:14:57 (*) Pipeline frontend
|
||||
Info: cpu: # 2021.05.27 17:14:57 (*) Pipeline backend
|
||||
Info: cpu: # 2021.05.27 17:14:59 (*) Generating RTL from CPU objects
|
||||
Info: cpu: # 2021.05.27 17:15:00 (*) Creating encrypted RTL
|
||||
Info: cpu: # 2021.05.27 17:15:01 (*) Done Nios II generation
|
||||
Info: cpu: Done RTL generation for module 'Qsys_nios2_gen2_cpu'
|
||||
Info: cpu: "nios2_gen2" instantiated altera_nios2_gen2_unit "cpu"
|
||||
Info: nios2_gen2_data_master_translator: "mm_interconnect_0" instantiated altera_merlin_master_translator "nios2_gen2_data_master_translator"
|
||||
Info: jtag_uart_avalon_jtag_slave_translator: "mm_interconnect_0" instantiated altera_merlin_slave_translator "jtag_uart_avalon_jtag_slave_translator"
|
||||
Info: nios2_gen2_data_master_agent: "mm_interconnect_0" instantiated altera_merlin_master_agent "nios2_gen2_data_master_agent"
|
||||
Info: jtag_uart_avalon_jtag_slave_agent: "mm_interconnect_0" instantiated altera_merlin_slave_agent "jtag_uart_avalon_jtag_slave_agent"
|
||||
Info: jtag_uart_avalon_jtag_slave_agent_rsp_fifo: "mm_interconnect_0" instantiated altera_avalon_sc_fifo "jtag_uart_avalon_jtag_slave_agent_rsp_fifo"
|
||||
Info: router: "mm_interconnect_0" instantiated altera_merlin_router "router"
|
||||
Info: router_001: "mm_interconnect_0" instantiated altera_merlin_router "router_001"
|
||||
Info: router_002: "mm_interconnect_0" instantiated altera_merlin_router "router_002"
|
||||
Info: router_006: "mm_interconnect_0" instantiated altera_merlin_router "router_006"
|
||||
Info: nios2_gen2_data_master_limiter: "mm_interconnect_0" instantiated altera_merlin_traffic_limiter "nios2_gen2_data_master_limiter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_sc_fifo.v
|
||||
Info: cmd_demux: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "cmd_demux"
|
||||
Info: cmd_demux_001: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "cmd_demux_001"
|
||||
Info: cmd_mux: "mm_interconnect_0" instantiated altera_merlin_multiplexer "cmd_mux"
|
||||
Info: cmd_mux_004: "mm_interconnect_0" instantiated altera_merlin_multiplexer "cmd_mux_004"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_demux: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux"
|
||||
Info: rsp_demux_004: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux_004"
|
||||
Info: rsp_demux_005: "mm_interconnect_0" instantiated altera_merlin_demultiplexer "rsp_demux_005"
|
||||
Info: rsp_mux: "mm_interconnect_0" instantiated altera_merlin_multiplexer "rsp_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_mux_001: "mm_interconnect_0" instantiated altera_merlin_multiplexer "rsp_mux_001"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: crosser: "mm_interconnect_0" instantiated altera_avalon_st_handshake_clock_crosser "crosser"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_st_pipeline_base.v
|
||||
Info: avalon_st_adapter: "mm_interconnect_0" instantiated altera_avalon_st_adapter "avalon_st_adapter"
|
||||
Info: router: "mm_interconnect_1" instantiated altera_merlin_router "router"
|
||||
Info: router_002: "mm_interconnect_1" instantiated altera_merlin_router "router_002"
|
||||
Info: sdram_s1_burst_adapter: "mm_interconnect_1" instantiated altera_merlin_burst_adapter "sdram_s1_burst_adapter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_avalon_st_pipeline_base.v
|
||||
Info: cmd_demux: "mm_interconnect_1" instantiated altera_merlin_demultiplexer "cmd_demux"
|
||||
Info: cmd_mux: "mm_interconnect_1" instantiated altera_merlin_multiplexer "cmd_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: rsp_demux: "mm_interconnect_1" instantiated altera_merlin_demultiplexer "rsp_demux"
|
||||
Info: rsp_mux: "mm_interconnect_1" instantiated altera_merlin_multiplexer "rsp_mux"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_arbitrator.sv
|
||||
Info: sdram_s1_rsp_width_adapter: "mm_interconnect_1" instantiated altera_merlin_width_adapter "sdram_s1_rsp_width_adapter"
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_address_alignment.sv
|
||||
Info: Reusing file C:/Users/Anish Ghanekar/OneDrive - Imperial College London/GitHub/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/Qsys/synthesis/submodules/altera_merlin_burst_uncompressor.sv
|
||||
Info: avalon_st_adapter: "mm_interconnect_1" instantiated altera_avalon_st_adapter "avalon_st_adapter"
|
||||
Info: error_adapter_0: "avalon_st_adapter" instantiated error_adapter "error_adapter_0"
|
||||
Info: error_adapter_0: "avalon_st_adapter" instantiated error_adapter "error_adapter_0"
|
||||
Info: Qsys: Done "Qsys" with 68 modules, 143 files
|
||||
Info: qsys-generate succeeded.
|
||||
Error: Generation stopped, 218 or more modules remaining
|
||||
Info: Qsys: Done "Qsys" with 33 modules, 34 files
|
||||
Error: qsys-generate failed with exit code 1: 8 Errors, 1 Warning
|
||||
Info: Finished: Create HDL design files for synthesis
|
||||
|
|
|
@ -40,6 +40,8 @@
|
|||
.terasic_camera_0_conduit_end_D (<connected-to-terasic_camera_0_conduit_end_D>), // terasic_camera_0_conduit_end.D
|
||||
.terasic_camera_0_conduit_end_FVAL (<connected-to-terasic_camera_0_conduit_end_FVAL>), // .FVAL
|
||||
.terasic_camera_0_conduit_end_LVAL (<connected-to-terasic_camera_0_conduit_end_LVAL>), // .LVAL
|
||||
.terasic_camera_0_conduit_end_PIXCLK (<connected-to-terasic_camera_0_conduit_end_PIXCLK>) // .PIXCLK
|
||||
.terasic_camera_0_conduit_end_PIXCLK (<connected-to-terasic_camera_0_conduit_end_PIXCLK>), // .PIXCLK
|
||||
.uart_0_rx_tx_rxd (<connected-to-uart_0_rx_tx_rxd>), // uart_0_rx_tx.rxd
|
||||
.uart_0_rx_tx_txd (<connected-to-uart_0_rx_tx_txd>) // .txd
|
||||
);
|
||||
|
||||
|
|
|
@ -41,7 +41,9 @@
|
|||
terasic_camera_0_conduit_end_D : in std_logic_vector(11 downto 0) := (others => 'X'); -- D
|
||||
terasic_camera_0_conduit_end_FVAL : in std_logic := 'X'; -- FVAL
|
||||
terasic_camera_0_conduit_end_LVAL : in std_logic := 'X'; -- LVAL
|
||||
terasic_camera_0_conduit_end_PIXCLK : in std_logic := 'X' -- PIXCLK
|
||||
terasic_camera_0_conduit_end_PIXCLK : in std_logic := 'X'; -- PIXCLK
|
||||
uart_0_rx_tx_rxd : in std_logic := 'X'; -- rxd
|
||||
uart_0_rx_tx_txd : out std_logic -- txd
|
||||
);
|
||||
end component Qsys;
|
||||
|
||||
|
@ -88,6 +90,8 @@
|
|||
terasic_camera_0_conduit_end_D => CONNECTED_TO_terasic_camera_0_conduit_end_D, -- terasic_camera_0_conduit_end.D
|
||||
terasic_camera_0_conduit_end_FVAL => CONNECTED_TO_terasic_camera_0_conduit_end_FVAL, -- .FVAL
|
||||
terasic_camera_0_conduit_end_LVAL => CONNECTED_TO_terasic_camera_0_conduit_end_LVAL, -- .LVAL
|
||||
terasic_camera_0_conduit_end_PIXCLK => CONNECTED_TO_terasic_camera_0_conduit_end_PIXCLK -- .PIXCLK
|
||||
terasic_camera_0_conduit_end_PIXCLK => CONNECTED_TO_terasic_camera_0_conduit_end_PIXCLK, -- .PIXCLK
|
||||
uart_0_rx_tx_rxd => CONNECTED_TO_uart_0_rx_tx_rxd, -- uart_0_rx_tx.rxd
|
||||
uart_0_rx_tx_txd => CONNECTED_TO_uart_0_rx_tx_txd -- .txd
|
||||
);
|
||||
|
||||
|
|
|
@ -1,12 +0,0 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<projectDescription>
|
||||
<name>RemoteSystemsTempFiles</name>
|
||||
<comment></comment>
|
||||
<projects>
|
||||
</projects>
|
||||
<buildSpec>
|
||||
</buildSpec>
|
||||
<natures>
|
||||
<nature>org.eclipse.rse.ui.remoteSystemsTempNature</nature>
|
||||
</natures>
|
||||
</projectDescription>
|
|
@ -72,25 +72,13 @@ parameter BB_COL_DEFAULT = 24'h00ff00;
|
|||
|
||||
wire [7:0] red, green, blue, grey;
|
||||
wire [7:0] red_out, green_out, blue_out;
|
||||
wire [8:0] hue;
|
||||
wire [7:0] saturation, value;
|
||||
|
||||
wire sop, eop, in_valid, out_ready;
|
||||
////////////////////////////////////////////////////////////////////////
|
||||
|
||||
// RGB --> HSV Conversion
|
||||
wire [7:0] min, max, delta;
|
||||
assign min = (red < green) ? ((red < blue) ? red : blue) : ((green < blue) ? green : blue);
|
||||
assign max = (red > green) ? ((red > blue) ? red : blue) : ((green > blue) ? green : blue);
|
||||
assign delta = max - min;
|
||||
assign hue = (red == max) ? (green - blue)/delta : ((green == max) ? 8'h55+((blue - red)/delta) : 8'haa+((red - green)/delta));
|
||||
assign saturation = (max == 8'h00) ? 8'h00 : delta / max;
|
||||
assign value = max;
|
||||
|
||||
// Detect red areas
|
||||
wire red_detect;
|
||||
//assign red_detect = red[7] & ~green[7] & ~blue[7];
|
||||
assign red_detect = blue[7];
|
||||
assign red_detect = red[7] & ~green[7] & ~blue[7];
|
||||
|
||||
// Find boundary of cursor box
|
||||
|
||||
|
|
|
@ -1,273 +0,0 @@
|
|||
/*
|
||||
Source: https://github.com/hildebrandmw/de10lite-hdl/blob/master/components/uart/hdl/uart.v
|
||||
Description: Very simple UART tx/rx module. Requires a streaming interface,
|
||||
provides no buffering for input or output data.
|
||||
*/
|
||||
|
||||
module uart
|
||||
#( parameter CLK_FREQ = 50_000_000,
|
||||
parameter BAUD = 115_200
|
||||
)
|
||||
( input clk,
|
||||
input reset,
|
||||
|
||||
// Receiving
|
||||
input rx, // Received serial stream
|
||||
output reg [7:0] rx_data, // Deserialized byte.
|
||||
output rx_valid, // Asserted when rx_data is valid
|
||||
|
||||
// Transmitting
|
||||
output reg tx, // Transmitted serial stream
|
||||
input [7:0] tx_data, // Deserialized byte to transmit.
|
||||
input tx_transmit, // Start Signal. No effect if tx_ready = 0
|
||||
output reg tx_ready // Asserted when ready to accept data
|
||||
);
|
||||
|
||||
///////////////////////////////
|
||||
// Functionality Description //
|
||||
///////////////////////////////
|
||||
|
||||
/*
|
||||
RECEIVING: Module receives a serial stream through the port rx.
|
||||
When a byte has been successfully received, the received data will be
|
||||
available on the output port rx_data and the output port rx_valid will be
|
||||
asserted for 1 clock cycle.
|
||||
|
||||
Validity of output data is not guaranteed if rx_valid is not 1. If this
|
||||
is important for you, you may modify this design to register the output.
|
||||
|
||||
TRANSMITTING: When input port tx_transmit is 1 (asserted), module will
|
||||
store the data on the input port tx_data and serialize through the output
|
||||
port tx.
|
||||
|
||||
Module will only save and transmit the data at tx_data if the signal
|
||||
tx_ready is asserted when tx_transmit is asserted. This module will not
|
||||
buffer input data. While transmitting, tx_ready is deasserted and the
|
||||
input port tx_transmit will have no effect.
|
||||
|
||||
Once tx_ready is deasserted, data at port tx_data is not used and need
|
||||
not be stable.
|
||||
*/
|
||||
|
||||
/////////////////////////
|
||||
// Signal Declarations //
|
||||
/////////////////////////
|
||||
|
||||
// ---------------------- //
|
||||
// -- Local Parameters -- //
|
||||
// ---------------------- //
|
||||
|
||||
// Number of synchronization stages to avoid metastability
|
||||
localparam SYNC_STAGES = 2;
|
||||
|
||||
// Over Sampling Factor
|
||||
localparam OSF = 16;
|
||||
|
||||
// Compute count to generate local clock enable
|
||||
localparam CLK_DIV_COUNT = CLK_FREQ / (OSF * BAUD);
|
||||
|
||||
// ---------------------------- //
|
||||
// -- Clock Dividing Counter -- //
|
||||
// ---------------------------- //
|
||||
|
||||
reg [15:0] count;
|
||||
reg enable; // Local Clock Enable
|
||||
|
||||
// -- RX Synchronizer --
|
||||
reg [SYNC_STAGES-1:0] rx_sync;
|
||||
reg rx_internal;
|
||||
|
||||
// ---------------- //
|
||||
// -- RX Signals -- //
|
||||
// ---------------- //
|
||||
|
||||
// State Machine Assignments
|
||||
localparam RX_WAIT = 0;
|
||||
localparam RX_CHECK_START = 1;
|
||||
localparam RX_RECEIVING = 2;
|
||||
localparam RX_WAIT_FOR_STOP = 3;
|
||||
|
||||
localparam RX_INITIAL_STATE = RX_WAIT;
|
||||
reg [1:0] rx_state = RX_INITIAL_STATE;
|
||||
|
||||
reg [4:0] rx_count; // Counts Over-sampling clock enables
|
||||
reg [2:0] rx_sampleCount; // Counts number of bits received
|
||||
|
||||
// These last two signals are used to make sure the "rx_valid" signal
|
||||
// is only asserted for one clock cycle.
|
||||
|
||||
reg rx_validInternal, rx_validLast;
|
||||
|
||||
// -----------------//
|
||||
// -- TX Signals -- //
|
||||
// -----------------//
|
||||
|
||||
// State Machine Assignments
|
||||
localparam TX_WAIT = 0;
|
||||
localparam TX_TRANSMITTING = 1;
|
||||
|
||||
localparam TX_INITIAL_STATE = TX_WAIT;
|
||||
reg tx_state = TX_INITIAL_STATE;
|
||||
|
||||
reg [9:0] tx_dataBuffer; // Capture Register for transmitted data
|
||||
reg [4:0] tx_count; // Counts over-sampling clock
|
||||
reg [3:0] tx_sampleCount; // Number of Bits Sent
|
||||
|
||||
/////////////////////
|
||||
// Implementations //
|
||||
/////////////////////
|
||||
|
||||
// ---------------------------- //
|
||||
// -- Misc Synchronous Logic -- //
|
||||
// ---------------------------- //
|
||||
|
||||
always @(posedge clk) begin
|
||||
|
||||
// Clock Divider
|
||||
if (reset) begin
|
||||
count <= 0;
|
||||
enable <= 0;
|
||||
end else if (count == CLK_DIV_COUNT - 1) begin
|
||||
count <= 0;
|
||||
enable <= 1;
|
||||
end else begin
|
||||
count <= count + 1;
|
||||
enable <= 0;
|
||||
end
|
||||
|
||||
// RX Synchronizer
|
||||
if (enable) begin
|
||||
{rx_sync,rx_internal} <= {rx, rx_sync};
|
||||
end
|
||||
|
||||
// Pulse Shortener for rx_valid signal
|
||||
rx_validLast <= rx_validInternal;
|
||||
end
|
||||
|
||||
// Pulse Shortner for rx_valid signal
|
||||
assign rx_valid = rx_validInternal & ~rx_validLast;
|
||||
|
||||
|
||||
// ---------------------- //
|
||||
// -- RX State Machine -- //
|
||||
// ---------------------- //
|
||||
|
||||
always @(posedge clk) begin
|
||||
if (reset) begin
|
||||
rx_state <= RX_INITIAL_STATE;
|
||||
rx_validInternal <= 0;
|
||||
end else if (enable) begin
|
||||
case (rx_state)
|
||||
|
||||
// Wait for the start bit. (RX = 0)
|
||||
|
||||
RX_WAIT: begin
|
||||
rx_validInternal <= 0;
|
||||
if (rx_internal == 0) begin
|
||||
rx_state <= RX_CHECK_START;
|
||||
rx_count <= 1;
|
||||
end
|
||||
end
|
||||
|
||||
// Aligh with center of transmitted bit
|
||||
|
||||
RX_CHECK_START: begin
|
||||
|
||||
// Check if RX is still 0
|
||||
if (rx_count == (OSF >> 1) - 1 && rx_internal == 0) begin
|
||||
rx_state <= RX_RECEIVING;
|
||||
rx_count <= 0;
|
||||
rx_sampleCount <= 0;
|
||||
|
||||
// Faulty Start Bit
|
||||
end else if (rx_count == (OSF >> 1) - 1 && rx_internal == 1) begin
|
||||
rx_state <= RX_WAIT;
|
||||
|
||||
// Default Option: Count local clocks
|
||||
end else begin
|
||||
rx_count <= rx_count + 1;
|
||||
end
|
||||
end
|
||||
|
||||
// Sample in middle of received bit. Shift data into rx_data
|
||||
RX_RECEIVING: begin
|
||||
if (rx_count == OSF - 1) begin
|
||||
rx_count <= 0;
|
||||
rx_data <= {rx_internal, rx_data[7:1]};
|
||||
rx_sampleCount <= rx_sampleCount + 1;
|
||||
|
||||
// Check if this is the last bit of data
|
||||
if (rx_sampleCount == 7) begin
|
||||
rx_state <= RX_WAIT_FOR_STOP;
|
||||
end
|
||||
end else begin
|
||||
rx_count <= rx_count + 1;
|
||||
end
|
||||
end
|
||||
|
||||
// Wait until stop bit is received
|
||||
// Not the best logic in the world, but it works.
|
||||
RX_WAIT_FOR_STOP: begin
|
||||
if (rx_internal == 1'b1) begin
|
||||
rx_state <= RX_WAIT;
|
||||
rx_validInternal <= 1;
|
||||
end
|
||||
end
|
||||
|
||||
// In case something goes horribly wrong.
|
||||
default: begin
|
||||
rx_state <= RX_INITIAL_STATE;
|
||||
end
|
||||
endcase
|
||||
end
|
||||
end
|
||||
|
||||
// ---------------------- //
|
||||
// -- TX State Machine -- //
|
||||
// ---------------------- //
|
||||
|
||||
always @(posedge clk) begin
|
||||
if (reset) begin
|
||||
tx_state <= TX_INITIAL_STATE;
|
||||
tx <= 1;
|
||||
end else begin
|
||||
case (tx_state)
|
||||
// Wait for start signal.
|
||||
// Register transmitted data and deassert ready.
|
||||
TX_WAIT: begin
|
||||
tx <= 1;
|
||||
if (tx_transmit) begin
|
||||
tx_dataBuffer <= {1'b1, tx_data, 1'b0};
|
||||
tx_count <= 0;
|
||||
tx_sampleCount <= 0;
|
||||
tx_ready <= 0;
|
||||
tx_state <= TX_TRANSMITTING;
|
||||
end else begin
|
||||
tx_ready <= 1;
|
||||
end
|
||||
end
|
||||
|
||||
// Shift Out Data
|
||||
TX_TRANSMITTING: begin
|
||||
if (enable) begin
|
||||
if (tx_count == OSF - 1) begin
|
||||
tx_count <= 0;
|
||||
tx_sampleCount <= tx_sampleCount + 1;
|
||||
tx <= tx_dataBuffer[0];
|
||||
tx_dataBuffer <= {1'b1, tx_dataBuffer[9:1]};
|
||||
if (tx_sampleCount == 9) begin
|
||||
tx_state <= TX_WAIT;
|
||||
end
|
||||
end else begin
|
||||
tx_count <= tx_count + 1;
|
||||
end
|
||||
end
|
||||
end
|
||||
|
||||
default: begin
|
||||
tx_state <= TX_WAIT;
|
||||
end
|
||||
endcase
|
||||
end
|
||||
end
|
||||
endmodule
|
|
@ -1,480 +0,0 @@
|
|||
!SESSION 2021-06-01 14:03:06.351 -----------------------------------------------
|
||||
eclipse.buildId=4.3.2.M20140221-1700
|
||||
java.version=1.8.0_05
|
||||
java.vendor=Oracle Corporation
|
||||
BootLoader constants: OS=linux, ARCH=x86_64, WS=gtk, NL=en_US
|
||||
Framework arguments: -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
Command-line arguments: -os linux -ws gtk -arch x86_64 -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 14:04:23.380
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 14:04:23.380
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 14:04:24.498
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 14:04:24.498
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY org.eclipse.cdt.core 1 0 2021-06-01 14:06:17.329
|
||||
!MESSAGE Indexed 'D8M_Camera_Test' (6 sources, 6 headers) in 0.60 sec: 306 declarations; 1,011 references; 24 unresolved inclusions; 0 syntax errors; 201 unresolved names (13.24%)
|
||||
|
||||
!ENTRY org.eclipse.cdt.core 1 0 2021-06-01 14:07:50.514
|
||||
!MESSAGE Indexed 'D8M_Camera_Test_bsp' (83 sources, 154 headers) in 1.78 sec: 5,266 declarations; 8,569 references; 16 unresolved inclusions; 2 syntax errors; 51 unresolved names (0.37%)
|
||||
|
||||
!ENTRY org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE Keybinding conflicts occurred. They may interfere with normal accelerator operation.
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for ALT+CTRL+I:
|
||||
Binding(ALT+CTRL+I,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.include.browser,Open Include Browser,
|
||||
Open an include browser on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@24090832,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+CTRL+I,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.include.browser,Open Include Browser,
|
||||
Open an include browser on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@24090832,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+T:
|
||||
Binding(CTRL+SHIFT+T,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.opentype,Open Element,
|
||||
Open an element in an Editor,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@7e38d2a2,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+T,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.opentype,Open Element,
|
||||
Open an element in an Editor,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@7e38d2a2,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for F4:
|
||||
Binding(F4,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.type.hierarchy,Open Type Hierarchy,
|
||||
Open a type hierarchy on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@79408109,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(F4,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.type.hierarchy,Open Type Hierarchy,
|
||||
Open a type hierarchy on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@79408109,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for ALT+SHIFT+R:
|
||||
Binding(ALT+SHIFT+R,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.text.rename.element,Rename - Refactoring ,
|
||||
Rename the selected element,
|
||||
Category(org.eclipse.cdt.ui.category.refactoring,Refactor - C++,C/C++ Refactorings,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@33671907,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+SHIFT+R,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.text.rename.element,Rename - Refactoring ,
|
||||
Rename the selected element,
|
||||
Category(org.eclipse.cdt.ui.category.refactoring,Refactor - C++,C/C++ Refactorings,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@33671907,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for F3:
|
||||
Binding(F3,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.opendecl,Open Declaration,
|
||||
Open an editor on the selected element's declaration(s),
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@5fc3dfc1,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(F3,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.opendecl,Open Declaration,
|
||||
Open an editor on the selected element's declaration(s),
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@5fc3dfc1,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+G:
|
||||
Binding(CTRL+SHIFT+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.findrefs,References,
|
||||
Search for references to the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@67d6bb59,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.findrefs,References,
|
||||
Search for references to the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@67d6bb59,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for CTRL+G:
|
||||
Binding(CTRL+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.finddecl,Declaration,
|
||||
Search for declarations of the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1a632663,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.finddecl,Declaration,
|
||||
Search for declarations of the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1a632663,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for ALT+CTRL+H:
|
||||
Binding(ALT+CTRL+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.call.hierarchy,Open Call Hierarchy,
|
||||
Open the call hierarchy for the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1147ab09,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+CTRL+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.call.hierarchy,Open Call Hierarchy,
|
||||
Open the call hierarchy for the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1147ab09,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 14:09:49.546
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+H:
|
||||
Binding(CTRL+SHIFT+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.open.type.in.hierarchy,Open Type in Hierarchy,
|
||||
Open a type in the type hierarchy view,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@503b5337,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.open.type.in.hierarchy,Open Type in Hierarchy,
|
||||
Open a type in the type hierarchy view,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@503b5337,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 14:11:37.605
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 14:11:39.859
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 14:35:55.217
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 14:35:58.889
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
!SESSION 2021-06-01 15:25:18.150 -----------------------------------------------
|
||||
eclipse.buildId=4.3.2.M20140221-1700
|
||||
java.version=1.8.0_05
|
||||
java.vendor=Oracle Corporation
|
||||
BootLoader constants: OS=linux, ARCH=x86_64, WS=gtk, NL=en_US
|
||||
Framework arguments: -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
Command-line arguments: -os linux -ws gtk -arch x86_64 -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
|
||||
!ENTRY org.eclipse.core.resources 2 10035 2021-06-01 15:25:34.463
|
||||
!MESSAGE The workspace exited with unsaved changes in the previous session; refreshing workspace to recover changes.
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 15:25:35.756
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 15:25:35.756
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 15:25:36.679
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 15:25:36.679
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:30:01.828
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:03.222
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --stop, --sidp=0x410e0, --id=0x0] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:30:04.718
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:06.290
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --go, --sidp=0x410e0, --id=0x0, /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:06.295
|
||||
!MESSAGE Downloading ELF Process failed
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:30:48.922
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:50.294
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --stop, --sidp=0x410e0, --id=0x0] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:30:51.067
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:52.474
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --go, --sidp=0x410e0, --id=0x0, /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:30:52.478
|
||||
!MESSAGE Downloading ELF Process failed
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:31:19.409
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:31:20.799
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --stop, --sidp=0x410e0, --id=0x0] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:31:21.477
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:31:22.936
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --go, --sidp=0x410e0, --id=0x0, /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:31:22.940
|
||||
!MESSAGE Downloading ELF Process failed
|
||||
|
||||
!ENTRY org.eclipse.cdt.core 1 0 2021-06-01 15:39:40.412
|
||||
!MESSAGE Indexed 'D8M_Camera_Test' (6 sources, 68 headers) in 0.40 sec: 2,546 declarations; 4,517 references; 0 unresolved inclusions; 0 syntax errors; 0 unresolved names (0.00%)
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:41:17.879
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:41:19.297
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --stop, --sidp=0x410e0, --id=0x0] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:41:19.587
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:41:21.001
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --go, --sidp=0x410e0, --id=0x0, /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:41:21.005
|
||||
!MESSAGE Downloading ELF Process failed
|
||||
!SESSION 2021-06-01 15:51:10.061 -----------------------------------------------
|
||||
eclipse.buildId=4.3.2.M20140221-1700
|
||||
java.version=1.8.0_05
|
||||
java.vendor=Oracle Corporation
|
||||
BootLoader constants: OS=linux, ARCH=x86_64, WS=gtk, NL=en_US
|
||||
Framework arguments: -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
Command-line arguments: -os linux -ws gtk -arch x86_64 -product org.eclipse.epp.package.cpp.product -pluginCustomization /usr/local/altera/16.0/nios2eds/bin/eclipse_nios2/plugin_customization.ini
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 15:51:21.549
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 15:51:21.549
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY org.eclipse.ui 2 0 2021-06-01 15:51:22.916
|
||||
!MESSAGE Warnings while parsing the commands from the 'org.eclipse.ui.commands' and 'org.eclipse.ui.actionDefinitions' extension points.
|
||||
!SUBENTRY 1 org.eclipse.ui 2 0 2021-06-01 15:51:22.916
|
||||
!MESSAGE Commands should really have a category: plug-in='org.eclipse.linuxtools.systemtap.ui.graphing', id='org.eclipse.linuxtools.systemtap.ui.graphing.commands.SaveGraphImage', categoryId='org.eclipse.linuxtools.systemtap.ui.graphing.category.file'
|
||||
|
||||
!ENTRY org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE Keybinding conflicts occurred. They may interfere with normal accelerator operation.
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for F3:
|
||||
Binding(F3,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.opendecl,Open Declaration,
|
||||
Open an editor on the selected element's declaration(s),
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@612bb755,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(F3,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.opendecl,Open Declaration,
|
||||
Open an editor on the selected element's declaration(s),
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@612bb755,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for ALT+CTRL+I:
|
||||
Binding(ALT+CTRL+I,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.include.browser,Open Include Browser,
|
||||
Open an include browser on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@6ba226cd,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+CTRL+I,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.include.browser,Open Include Browser,
|
||||
Open an include browser on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@6ba226cd,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for F4:
|
||||
Binding(F4,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.type.hierarchy,Open Type Hierarchy,
|
||||
Open a type hierarchy on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@62e99458,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(F4,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.type.hierarchy,Open Type Hierarchy,
|
||||
Open a type hierarchy on the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@62e99458,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for ALT+SHIFT+R:
|
||||
Binding(ALT+SHIFT+R,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.text.rename.element,Rename - Refactoring ,
|
||||
Rename the selected element,
|
||||
Category(org.eclipse.cdt.ui.category.refactoring,Refactor - C++,C/C++ Refactorings,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1eddca25,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+SHIFT+R,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.text.rename.element,Rename - Refactoring ,
|
||||
Rename the selected element,
|
||||
Category(org.eclipse.cdt.ui.category.refactoring,Refactor - C++,C/C++ Refactorings,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@1eddca25,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+G:
|
||||
Binding(CTRL+SHIFT+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.findrefs,References,
|
||||
Search for references to the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@22f057b4,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.findrefs,References,
|
||||
Search for references to the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@22f057b4,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for CTRL+G:
|
||||
Binding(CTRL+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.finddecl,Declaration,
|
||||
Search for declarations of the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@581e8969,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+G,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.search.finddecl,Declaration,
|
||||
Search for declarations of the selected element in the workspace,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@581e8969,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for ALT+CTRL+H:
|
||||
Binding(ALT+CTRL+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.call.hierarchy,Open Call Hierarchy,
|
||||
Open the call hierarchy for the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@767b9d66,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(ALT+CTRL+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.edit.open.call.hierarchy,Open Call Hierarchy,
|
||||
Open the call hierarchy for the selected element,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@767b9d66,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+H:
|
||||
Binding(CTRL+SHIFT+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.open.type.in.hierarchy,Open Type in Hierarchy,
|
||||
Open a type in the type hierarchy view,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@687fd6e,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+H,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.open.type.in.hierarchy,Open Type in Hierarchy,
|
||||
Open a type in the type hierarchy view,
|
||||
Category(org.eclipse.ui.category.navigate,Navigate,null,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@687fd6e,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
!SUBENTRY 1 org.eclipse.jface 2 0 2021-06-01 15:51:50.182
|
||||
!MESSAGE A conflict occurred for CTRL+SHIFT+T:
|
||||
Binding(CTRL+SHIFT+T,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.opentype,Open Element,
|
||||
Open an element in an Editor,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@266a47fd,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cEditorScope,,,system)
|
||||
Binding(CTRL+SHIFT+T,
|
||||
ParameterizedCommand(Command(org.eclipse.cdt.ui.navigate.opentype,Open Element,
|
||||
Open an element in an Editor,
|
||||
Category(org.eclipse.cdt.ui.category.source,Source,Source commands,true),
|
||||
org.eclipse.ui.internal.WorkbenchHandlerServiceHandler@266a47fd,
|
||||
,,true),null),
|
||||
org.eclipse.ui.defaultAcceleratorConfiguration,
|
||||
org.eclipse.cdt.ui.cViewScope,,,system)
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:53:32.747
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --stop --sidp=0x410e0 --id=0x0]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:53:34.132
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --stop, --sidp=0x410e0, --id=0x0] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 1 0 2021-06-01 15:53:34.450
|
||||
!MESSAGE Executing: [/bin/bash, -c, nios2-download '--cable=USB-Blaster on 129.31.224.137 [USB-0]' --device=1 --instance=0 --go --sidp=0x410e0 --id=0x0 /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf]
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:53:36.047
|
||||
!MESSAGE Failed Executing: [nios2-download, '--cable=USB-Blaster on 129.31.224.137 [USB-0]', --device=1, --instance=0, --go, --sidp=0x410e0, --id=0x0, /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test/D8M_Camera_Test.elf] return code: 8
|
||||
|
||||
!ENTRY com.altera.sbtgui.launch 4 0 2021-06-01 15:53:36.052
|
||||
!MESSAGE Downloading ELF Process failed
|
Binary file not shown.
|
@ -1,2 +0,0 @@
|
|||
*** SESSION Jun 01, 2021 15:25:39.63 -------------------------------------------
|
||||
*** SESSION Jun 01, 2021 15:51:26.00 -------------------------------------------
|
Binary file not shown.
File diff suppressed because it is too large
Load diff
Binary file not shown.
File diff suppressed because it is too large
Load diff
|
@ -1 +0,0 @@
|
|||
|
|
@ -1 +0,0 @@
|
|||
|
|
@ -1,9 +0,0 @@
|
|||
15:53:28 **** Incremental Build of configuration Nios II for project D8M_Camera_Test ****
|
||||
make all
|
||||
Info: Building ../D8M_Camera_Test_bsp/
|
||||
make --no-print-directory -C ../D8M_Camera_Test_bsp/
|
||||
[BSP build complete]
|
||||
[D8M_Camera_Test build complete]
|
||||
|
||||
15:53:28 Build Finished (took 237ms)
|
||||
|
|
@ -1,129 +0,0 @@
|
|||
15:52:33 **** Build of configuration Nios II for project D8M_Camera_Test_bsp ****
|
||||
make all
|
||||
Compiling alt_alarm_start.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_alarm_start.o HAL/src/alt_alarm_start.c
|
||||
Compiling alt_busy_sleep.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_busy_sleep.o HAL/src/alt_busy_sleep.c
|
||||
Compiling alt_close.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_close.o HAL/src/alt_close.c
|
||||
Compiling alt_dcache_flush.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dcache_flush.o HAL/src/alt_dcache_flush.c
|
||||
Compiling alt_dcache_flush_all.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dcache_flush_all.o HAL/src/alt_dcache_flush_all.c
|
||||
Compiling alt_dcache_flush_no_writeback.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dcache_flush_no_writeback.o HAL/src/alt_dcache_flush_no_writeback.c
|
||||
Compiling alt_dev.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dev.o HAL/src/alt_dev.c
|
||||
Compiling alt_dma_rxchan_open.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dma_rxchan_open.o HAL/src/alt_dma_rxchan_open.c
|
||||
Compiling alt_dma_txchan_open.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_dma_txchan_open.o HAL/src/alt_dma_txchan_open.c
|
||||
Compiling alt_ecc_fatal_exception.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_ecc_fatal_exception.o HAL/src/alt_ecc_fatal_exception.c
|
||||
Compiling alt_exception_entry.S...
|
||||
nios2-elf-gcc -MP -MMD -c -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -Wa,-gdwarf2 -o obj/HAL/src/alt_exception_entry.o HAL/src/alt_exception_entry.S
|
||||
Compiling alt_exit.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_exit.o HAL/src/alt_exit.c
|
||||
Compiling alt_fcntl.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_fcntl.o HAL/src/alt_fcntl.c
|
||||
Compiling alt_fd_lock.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_fd_lock.o HAL/src/alt_fd_lock.c
|
||||
Compiling alt_fd_unlock.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_fd_unlock.o HAL/src/alt_fd_unlock.c
|
||||
Compiling alt_find_dev.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_find_dev.o HAL/src/alt_find_dev.c
|
||||
Compiling alt_find_file.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_find_file.o HAL/src/alt_find_file.c
|
||||
Compiling alt_flash_dev.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_flash_dev.o HAL/src/alt_flash_dev.c
|
||||
Compiling alt_fs_reg.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_fs_reg.o HAL/src/alt_fs_reg.c
|
||||
Compiling alt_fstat.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_fstat.o HAL/src/alt_fstat.c
|
||||
Compiling alt_get_fd.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_get_fd.o HAL/src/alt_get_fd.c
|
||||
Compiling alt_gmon.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_gmon.o HAL/src/alt_gmon.c
|
||||
Compiling alt_icache_flush.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_icache_flush.o HAL/src/alt_icache_flush.c
|
||||
Compiling alt_icache_flush_all.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_icache_flush_all.o HAL/src/alt_icache_flush_all.c
|
||||
Compiling alt_iic.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_iic.o HAL/src/alt_iic.c
|
||||
Compiling alt_iic_isr_register.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_iic_isr_register.o HAL/src/alt_iic_isr_register.c
|
||||
Compiling alt_instruction_exception_entry.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_instruction_exception_entry.o HAL/src/alt_instruction_exception_entry.c
|
||||
Compiling alt_instruction_exception_register.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_instruction_exception_register.o HAL/src/alt_instruction_exception_register.c
|
||||
Compiling alt_io_redirect.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_io_redirect.o HAL/src/alt_io_redirect.c
|
||||
Compiling alt_ioctl.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_ioctl.o HAL/src/alt_ioctl.c
|
||||
Compiling alt_irq_entry.S...
|
||||
nios2-elf-gcc -MP -MMD -c -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -Wa,-gdwarf2 -o obj/HAL/src/alt_irq_entry.o HAL/src/alt_irq_entry.S
|
||||
Compiling alt_irq_handler.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_irq_handler.o HAL/src/alt_irq_handler.c
|
||||
Compiling alt_irq_register.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_irq_register.o HAL/src/alt_irq_register.c
|
||||
Compiling alt_irq_vars.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_irq_vars.o HAL/src/alt_irq_vars.c
|
||||
Compiling alt_isatty.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_isatty.o HAL/src/alt_isatty.c
|
||||
Compiling alt_lseek.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_lseek.o HAL/src/alt_lseek.c
|
||||
Compiling alt_main.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_main.o HAL/src/alt_main.c
|
||||
Compiling alt_open.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_open.o HAL/src/alt_open.c
|
||||
Compiling alt_read.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_read.o HAL/src/alt_read.c
|
||||
Compiling alt_release_fd.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_release_fd.o HAL/src/alt_release_fd.c
|
||||
Compiling alt_remap_cached.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_remap_cached.o HAL/src/alt_remap_cached.c
|
||||
Compiling alt_remap_uncached.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_remap_uncached.o HAL/src/alt_remap_uncached.c
|
||||
Compiling alt_sbrk.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_sbrk.o HAL/src/alt_sbrk.c
|
||||
Compiling alt_software_exception.S...
|
||||
nios2-elf-gcc -MP -MMD -c -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -Wa,-gdwarf2 -o obj/HAL/src/alt_software_exception.o HAL/src/alt_software_exception.S
|
||||
Compiling alt_tick.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_tick.o HAL/src/alt_tick.c
|
||||
Compiling alt_uncached_free.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_uncached_free.o HAL/src/alt_uncached_free.c
|
||||
Compiling alt_uncached_malloc.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_uncached_malloc.o HAL/src/alt_uncached_malloc.c
|
||||
Compiling alt_write.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/alt_write.o HAL/src/alt_write.c
|
||||
Compiling altera_nios2_gen2_irq.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/HAL/src/altera_nios2_gen2_irq.o HAL/src/altera_nios2_gen2_irq.c
|
||||
Compiling crt0.S...
|
||||
nios2-elf-gcc -MP -MMD -c -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -Wa,-gdwarf2 -o obj/HAL/src/crt0.o HAL/src/crt0.S
|
||||
Compiling alt_sys_init.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/alt_sys_init.o alt_sys_init.c
|
||||
Compiling altera_avalon_jtag_uart_fd.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_jtag_uart_fd.o drivers/src/altera_avalon_jtag_uart_fd.c
|
||||
Compiling altera_avalon_jtag_uart_init.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_jtag_uart_init.o drivers/src/altera_avalon_jtag_uart_init.c
|
||||
Compiling altera_avalon_jtag_uart_ioctl.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_jtag_uart_ioctl.o drivers/src/altera_avalon_jtag_uart_ioctl.c
|
||||
Compiling altera_avalon_jtag_uart_read.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_jtag_uart_read.o drivers/src/altera_avalon_jtag_uart_read.c
|
||||
Compiling altera_avalon_jtag_uart_write.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_jtag_uart_write.o drivers/src/altera_avalon_jtag_uart_write.c
|
||||
Compiling altera_avalon_sysid_qsys.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_sysid_qsys.o drivers/src/altera_avalon_sysid_qsys.c
|
||||
Compiling altera_avalon_timer_sc.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_timer_sc.o drivers/src/altera_avalon_timer_sc.c
|
||||
Compiling altera_avalon_timer_ts.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_timer_ts.o drivers/src/altera_avalon_timer_ts.c
|
||||
Compiling altera_avalon_timer_vars.c...
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I./HAL/inc -I. -I./drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mgpopt=local -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/drivers/src/altera_avalon_timer_vars.o drivers/src/altera_avalon_timer_vars.c
|
||||
Creating libhal_bsp.a...
|
||||
rm -f -f libhal_bsp.a
|
||||
nios2-elf-ar -src libhal_bsp.a obj/HAL/src/alt_alarm_start.o obj/HAL/src/alt_busy_sleep.o obj/HAL/src/alt_close.o obj/HAL/src/alt_dcache_flush.o obj/HAL/src/alt_dcache_flush_all.o obj/HAL/src/alt_dcache_flush_no_writeback.o obj/HAL/src/alt_dev.o obj/HAL/src/alt_dev_llist_insert.o obj/HAL/src/alt_dma_rxchan_open.o obj/HAL/src/alt_dma_txchan_open.o obj/HAL/src/alt_do_ctors.o obj/HAL/src/alt_do_dtors.o obj/HAL/src/alt_ecc_fatal_entry.o obj/HAL/src/alt_ecc_fatal_exception.o obj/HAL/src/alt_env_lock.o obj/HAL/src/alt_environ.o obj/HAL/src/alt_errno.o obj/HAL/src/alt_exception_entry.o obj/HAL/src/alt_exception_muldiv.o obj/HAL/src/alt_exception_trap.o obj/HAL/src/alt_execve.o obj/HAL/src/alt_exit.o obj/HAL/src/alt_fcntl.o obj/HAL/src/alt_fd_lock.o obj/HAL/src/alt_fd_unlock.o obj/HAL/src/alt_find_dev.o obj/HAL/src/alt_find_file.o obj/HAL/src/alt_flash_dev.o obj/HAL/src/alt_fork.o obj/HAL/src/alt_fs_reg.o obj/HAL/src/alt_fstat.o obj/HAL/src/alt_get_fd.o obj/HAL/src/alt_getchar.o obj/HAL/src/alt_getpid.o obj/HAL/src/alt_gettod.o obj/HAL/src/alt_gmon.o obj/HAL/src/alt_icache_flush.o obj/HAL/src/alt_icache_flush_all.o obj/HAL/src/alt_iic.o obj/HAL/src/alt_iic_isr_register.o obj/HAL/src/alt_instruction_exception_entry.o obj/HAL/src/alt_instruction_exception_register.o obj/HAL/src/alt_io_redirect.o obj/HAL/src/alt_ioctl.o obj/HAL/src/alt_irq_entry.o obj/HAL/src/alt_irq_handler.o obj/HAL/src/alt_irq_register.o obj/HAL/src/alt_irq_vars.o obj/HAL/src/alt_isatty.o obj/HAL/src/alt_kill.o obj/HAL/src/alt_link.o obj/HAL/src/alt_load.o obj/HAL/src/alt_log_macro.o obj/HAL/src/alt_log_printf.o obj/HAL/src/alt_lseek.o obj/HAL/src/alt_main.o obj/HAL/src/alt_malloc_lock.o obj/HAL/src/alt_mcount.o obj/HAL/src/alt_open.o obj/HAL/src/alt_printf.o obj/HAL/src/alt_putchar.o obj/HAL/src/alt_putcharbuf.o obj/HAL/src/alt_putstr.o obj/HAL/src/alt_read.o obj/HAL/src/alt_release_fd.o obj/HAL/src/alt_remap_cached.o obj/HAL/src/alt_remap_uncached.o obj/HAL/src/alt_rename.o obj/HAL/src/alt_sbrk.o obj/HAL/src/alt_settod.o obj/HAL/src/alt_software_exception.o obj/HAL/src/alt_stat.o obj/HAL/src/alt_tick.o obj/HAL/src/alt_times.o obj/HAL/src/alt_uncached_free.o obj/HAL/src/alt_uncached_malloc.o obj/HAL/src/alt_unlink.o obj/HAL/src/alt_usleep.o obj/HAL/src/alt_wait.o obj/HAL/src/alt_write.o obj/HAL/src/altera_nios2_gen2_irq.o obj/HAL/src/crt0.o obj/alt_sys_init.o obj/drivers/src/altera_avalon_jtag_uart_fd.o obj/drivers/src/altera_avalon_jtag_uart_init.o obj/drivers/src/altera_avalon_jtag_uart_ioctl.o obj/drivers/src/altera_avalon_jtag_uart_read.o obj/drivers/src/altera_avalon_jtag_uart_write.o obj/drivers/src/altera_avalon_sysid_qsys.o obj/drivers/src/altera_avalon_timer_sc.o obj/drivers/src/altera_avalon_timer_ts.o obj/drivers/src/altera_avalon_timer_vars.o
|
||||
[BSP build complete]
|
||||
|
||||
15:52:36 Build Finished (took 2s.792ms)
|
||||
|
|
@ -1,7 +0,0 @@
|
|||
<?xml version="1.0" encoding="UTF-8"?>
|
||||
<section name="Workbench">
|
||||
<section name="org.eclipse.cdt.ui.text.hover.CMacroExpansionExploration">
|
||||
</section>
|
||||
<section name="completion_proposal_size">
|
||||
</section>
|
||||
</section>
|
|
@ -1,61 +0,0 @@
|
|||
15:53:05 **** Build of configuration Nios II for project D8M_Camera_Test ****
|
||||
make all
|
||||
Info: Building ../D8M_Camera_Test_bsp/
|
||||
make --no-print-directory -C ../D8M_Camera_Test_bsp/
|
||||
[BSP build complete]
|
||||
Info: Compiling I2C_core.c to obj/default/I2C_core.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/I2C_core.o I2C_core.c
|
||||
I2C_core.c: In function 'oc_i2c_uninit':
|
||||
I2C_core.c:146:15: warning: unknown escape sequence: '\I'
|
||||
printf("\I2C core is failed to disable! \r\n");
|
||||
^
|
||||
I2C_core.c: In function 'OC_I2CL_Read':
|
||||
I2C_core.c:612:22: warning: unused variable 'DataLow' [-Wunused-variable]
|
||||
alt_u8 DataHigh, DataLow;
|
||||
^
|
||||
I2C_core.c:612:12: warning: unused variable 'DataHigh' [-Wunused-variable]
|
||||
alt_u8 DataHigh, DataLow;
|
||||
^
|
||||
Info: Compiling auto_focus.c to obj/default/auto_focus.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/auto_focus.o auto_focus.c
|
||||
auto_focus.c: In function 'Focus_Window':
|
||||
auto_focus.c:80:11: warning: 'end_focus' may be used uninitialized in this function [-Wmaybe-uninitialized]
|
||||
return end_focus;
|
||||
^
|
||||
Info: Compiling main.c to obj/default/main.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/main.o main.c
|
||||
main.c: In function 'main':
|
||||
main.c:233:20: warning: format '%x' expects argument of type 'unsigned int', but argument 2 has type 'alt_u32 {aka long unsigned int}' [-Wformat=]
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
^
|
||||
main.c:233:20: warning: format '%x' expects argument of type 'unsigned int', but argument 2 has type 'alt_u32 {aka long unsigned int}' [-Wformat=]
|
||||
main.c:238:20: warning: format '%x' expects argument of type 'unsigned int', but argument 2 has type 'alt_u32 {aka long unsigned int}' [-Wformat=]
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
^
|
||||
main.c:238:20: warning: format '%x' expects argument of type 'unsigned int', but argument 2 has type 'alt_u32 {aka long unsigned int}' [-Wformat=]
|
||||
Info: Compiling mipi_bridge_config.c to obj/default/mipi_bridge_config.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/mipi_bridge_config.o mipi_bridge_config.c
|
||||
Info: Compiling mipi_camera_config.c to obj/default/mipi_camera_config.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/mipi_camera_config.o mipi_camera_config.c
|
||||
Info: Compiling queue.c to obj/default/queue.o
|
||||
nios2-elf-gcc -xc -MP -MMD -c -I../D8M_Camera_Test_bsp//HAL/inc -I../D8M_Camera_Test_bsp/ -I../D8M_Camera_Test_bsp//drivers/inc -pipe -D__hal__ -DALT_NO_INSTRUCTION_EMULATION -DALT_SINGLE_THREADED -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o obj/default/queue.o queue.c
|
||||
Info: Linking D8M_Camera_Test.elf
|
||||
nios2-elf-g++ -T'../D8M_Camera_Test_bsp//linker.x' -msys-crt0='../D8M_Camera_Test_bsp//obj/HAL/src/crt0.o' -msys-lib=hal_bsp -L../D8M_Camera_Test_bsp/ -Wl,-Map=D8M_Camera_Test.map -O0 -g -Wall -mno-hw-div -mhw-mul -mno-hw-mulx -o D8M_Camera_Test.elf obj/default/I2C_core.o obj/default/auto_focus.o obj/default/main.o obj/default/mipi_bridge_config.o obj/default/mipi_camera_config.o obj/default/queue.o -lm -msys-lib=m
|
||||
nios2-elf-insert D8M_Camera_Test.elf --thread_model hal --cpu_name nios2_gen2 --qsys true --simulation_enabled false --id 0 --sidp 0x410e0 --timestamp 1622558600 --stderr_dev jtag_uart --stdin_dev jtag_uart --stdout_dev jtag_uart --sopc_system_name Qsys --quartus_project_dir "/home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16" --jdi ../..//output_files/DE10_LITE_D8M_VIP.jdi --sopcinfo /home/ad3919/nfshome/EE2Rover/Vision/DE10_LITE_D8M_VIP_16/software/D8M_Camera_Test_bsp/../../Qsys.sopcinfo
|
||||
Info: (D8M_Camera_Test.elf) 84 KBytes program size (code + initialized data).
|
||||
Info: 5096 Bytes free for stack + heap.
|
||||
Info: Creating D8M_Camera_Test.objdump
|
||||
nios2-elf-objdump --disassemble --syms --all-header --source D8M_Camera_Test.elf >D8M_Camera_Test.objdump
|
||||
[D8M_Camera_Test build complete]
|
||||
15:53:25 **** Build of configuration Nios II for project D8M_Camera_Test ****
|
||||
make all
|
||||
Info: Building ../D8M_Camera_Test_bsp/
|
||||
make --no-print-directory -C ../D8M_Camera_Test_bsp/
|
||||
[BSP build complete]
|
||||
[D8M_Camera_Test build complete]
|
||||
15:53:28 **** Incremental Build of configuration Nios II for project D8M_Camera_Test ****
|
||||
make all
|
||||
Info: Building ../D8M_Camera_Test_bsp/
|
||||
make --no-print-directory -C ../D8M_Camera_Test_bsp/
|
||||
[BSP build complete]
|
||||
[D8M_Camera_Test build complete]
|
|
@ -1,302 +0,0 @@
|
|||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "I2C_core.h"
|
||||
#include "terasic_includes.h"
|
||||
#include "mipi_camera_config.h"
|
||||
#include "mipi_bridge_config.h"
|
||||
#include "system.h"
|
||||
|
||||
#include "auto_focus.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
//EEE_IMGPROC defines
|
||||
#define EEE_IMGPROC_MSG_START ('R'<<16 | 'B'<<8 | 'B')
|
||||
|
||||
//offsets
|
||||
#define EEE_IMGPROC_STATUS 0
|
||||
#define EEE_IMGPROC_MSG 1
|
||||
#define EEE_IMGPROC_ID 2
|
||||
#define EEE_IMGPROC_BBCOL 3
|
||||
|
||||
#define EXPOSURE_INIT 0x002000
|
||||
#define EXPOSURE_STEP 0x100
|
||||
#define GAIN_INIT 0xFFF
|
||||
#define GAIN_STEP 0xFFF
|
||||
#define DEFAULT_LEVEL 3
|
||||
|
||||
#define MIPI_REG_PHYClkCtl 0x0056
|
||||
#define MIPI_REG_PHYData0Ctl 0x0058
|
||||
#define MIPI_REG_PHYData1Ctl 0x005A
|
||||
#define MIPI_REG_PHYData2Ctl 0x005C
|
||||
#define MIPI_REG_PHYData3Ctl 0x005E
|
||||
#define MIPI_REG_PHYTimDly 0x0060
|
||||
#define MIPI_REG_PHYSta 0x0062
|
||||
#define MIPI_REG_CSIStatus 0x0064
|
||||
#define MIPI_REG_CSIErrEn 0x0066
|
||||
#define MIPI_REG_MDLSynErr 0x0068
|
||||
#define MIPI_REG_FrmErrCnt 0x0080
|
||||
#define MIPI_REG_MDLErrCnt 0x0090
|
||||
|
||||
void mipi_clear_error(void){
|
||||
MipiBridgeRegWrite(MIPI_REG_CSIStatus,0x01FF); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLSynErr,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_FrmErrCnt,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLErrCnt, 0x0000); // clear error
|
||||
|
||||
MipiBridgeRegWrite(0x0082,0x00);
|
||||
MipiBridgeRegWrite(0x0084,0x00);
|
||||
MipiBridgeRegWrite(0x0086,0x00);
|
||||
MipiBridgeRegWrite(0x0088,0x00);
|
||||
MipiBridgeRegWrite(0x008A,0x00);
|
||||
MipiBridgeRegWrite(0x008C,0x00);
|
||||
MipiBridgeRegWrite(0x008E,0x00);
|
||||
MipiBridgeRegWrite(0x0090,0x00);
|
||||
}
|
||||
|
||||
void mipi_show_error_info(void){
|
||||
|
||||
alt_u16 PHY_status, SCI_status, MDLSynErr, FrmErrCnt, MDLErrCnt;
|
||||
|
||||
PHY_status = MipiBridgeRegRead(MIPI_REG_PHYSta);
|
||||
SCI_status = MipiBridgeRegRead(MIPI_REG_CSIStatus);
|
||||
MDLSynErr = MipiBridgeRegRead(MIPI_REG_MDLSynErr);
|
||||
FrmErrCnt = MipiBridgeRegRead(MIPI_REG_FrmErrCnt);
|
||||
MDLErrCnt = MipiBridgeRegRead(MIPI_REG_MDLErrCnt);
|
||||
printf("PHY_status=%xh, CSI_status=%xh, MDLSynErr=%xh, FrmErrCnt=%xh, MDLErrCnt=%xh\r\n", PHY_status, SCI_status, MDLSynErr,FrmErrCnt, MDLErrCnt);
|
||||
}
|
||||
|
||||
void mipi_show_error_info_more(void){
|
||||
printf("FrmErrCnt = %d\n",MipiBridgeRegRead(0x0080));
|
||||
printf("CRCErrCnt = %d\n",MipiBridgeRegRead(0x0082));
|
||||
printf("CorErrCnt = %d\n",MipiBridgeRegRead(0x0084));
|
||||
printf("HdrErrCnt = %d\n",MipiBridgeRegRead(0x0086));
|
||||
printf("EIDErrCnt = %d\n",MipiBridgeRegRead(0x0088));
|
||||
printf("CtlErrCnt = %d\n",MipiBridgeRegRead(0x008A));
|
||||
printf("SoTErrCnt = %d\n",MipiBridgeRegRead(0x008C));
|
||||
printf("SynErrCnt = %d\n",MipiBridgeRegRead(0x008E));
|
||||
printf("MDLErrCnt = %d\n",MipiBridgeRegRead(0x0090));
|
||||
printf("FIFOSTATUS = %d\n",MipiBridgeRegRead(0x00F8));
|
||||
printf("DataType = 0x%04x\n",MipiBridgeRegRead(0x006A));
|
||||
printf("CSIPktLen = %d\n",MipiBridgeRegRead(0x006E));
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool MIPI_Init(void){
|
||||
bool bSuccess;
|
||||
|
||||
|
||||
bSuccess = oc_i2c_init_ex(I2C_OPENCORES_MIPI_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
if (!bSuccess)
|
||||
printf("failed to init MIPI- Bridge i2c\r\n");
|
||||
|
||||
usleep(50*1000);
|
||||
MipiBridgeInit();
|
||||
|
||||
usleep(500*1000);
|
||||
|
||||
// bSuccess = oc_i2c_init_ex(I2C_OPENCORES_CAMERA_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
// if (!bSuccess)
|
||||
// printf("failed to init MIPI- Camera i2c\r\n");
|
||||
|
||||
MipiCameraInit();
|
||||
MIPI_BIN_LEVEL(DEFAULT_LEVEL);
|
||||
// OV8865_FOCUS_Move_to(340);
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_CAMERA_BASE); // Release I2C bus , due to two I2C master shared!
|
||||
|
||||
|
||||
usleep(1000);
|
||||
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_MIPI_BASE);
|
||||
|
||||
return bSuccess;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);
|
||||
|
||||
printf("DE10-LITE D8M VGA Demo\n");
|
||||
printf("Imperial College EEE2 Project version\n");
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0x00);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0x00);
|
||||
|
||||
usleep(2000);
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0xFF);
|
||||
usleep(2000);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0xFF);
|
||||
|
||||
printf("Image Processor ID: %x\n",IORD(0x42000,EEE_IMGPROC_ID));
|
||||
//printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID)); //Don't know why this doesn't work - definition is in system.h in BSP
|
||||
|
||||
|
||||
usleep(2000);
|
||||
|
||||
|
||||
// MIPI Init
|
||||
if (!MIPI_Init()){
|
||||
printf("MIPI_Init Init failed!\r\n");
|
||||
}else{
|
||||
printf("MIPI_Init Init successfully!\r\n");
|
||||
}
|
||||
|
||||
// while(1){
|
||||
mipi_clear_error();
|
||||
usleep(50*1000);
|
||||
mipi_clear_error();
|
||||
usleep(1000*1000);
|
||||
mipi_show_error_info();
|
||||
// mipi_show_error_info_more();
|
||||
printf("\n");
|
||||
// }
|
||||
|
||||
|
||||
#if 0 // focus sweep
|
||||
printf("\nFocus sweep\n");
|
||||
alt_u16 ii= 350;
|
||||
alt_u8 dir = 0;
|
||||
while(1){
|
||||
if(ii< 50) dir = 1;
|
||||
else if (ii> 1000) dir =0;
|
||||
|
||||
if(dir) ii += 20;
|
||||
else ii -= 20;
|
||||
|
||||
printf("%d\n",ii);
|
||||
OV8865_FOCUS_Move_to(ii);
|
||||
usleep(50*1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////
|
||||
alt_u16 bin_level = DEFAULT_LEVEL;
|
||||
alt_u8 manual_focus_step = 10;
|
||||
alt_u16 current_focus = 300;
|
||||
int boundingBoxColour = 0;
|
||||
alt_u32 exposureTime = EXPOSURE_INIT;
|
||||
alt_u16 gain = GAIN_INIT;
|
||||
|
||||
OV8865SetExposure(exposureTime);
|
||||
OV8865SetGain(gain);
|
||||
Focus_Init();
|
||||
while(1){
|
||||
|
||||
// touch KEY0 to trigger Auto focus
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x02){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
// touch KEY1 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x01){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0E){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
|
||||
// touch KEY1 to trigger Manual focus - step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0D){
|
||||
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
else current_focus = 0;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
|
||||
}
|
||||
|
||||
// touch KEY2 to trigger Manual focus + step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0B){
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
}
|
||||
|
||||
// touch KEY3 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x07){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
//Read messages from the image processor and print them on the terminal
|
||||
while ((IORD(0x42000,EEE_IMGPROC_STATUS)>>8) & 0xff) { //Find out if there are words to read
|
||||
int word = IORD(0x42000,EEE_IMGPROC_MSG); //Get next word from message buffer
|
||||
if (word == EEE_IMGPROC_MSG_START){ //Newline on message identifier
|
||||
printf("\n");
|
||||
}
|
||||
printf("%08x ",word);
|
||||
}
|
||||
|
||||
//Update the bounding box colour
|
||||
boundingBoxColour = ((boundingBoxColour + 1) & 0xff);
|
||||
IOWR(0x42000, EEE_IMGPROC_BBCOL, (boundingBoxColour << 8) | (0xff - boundingBoxColour));
|
||||
|
||||
//Process input commands
|
||||
int in = getchar();
|
||||
switch (in) {
|
||||
case 'e': {
|
||||
exposureTime += EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 'd': {
|
||||
exposureTime -= EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 't': {
|
||||
gain += GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'g': {
|
||||
gain -= GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'r': {
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
case 'f': {
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
}
|
||||
|
||||
|
||||
//Main loop delay
|
||||
usleep(10000);
|
||||
|
||||
};
|
||||
return 0;
|
||||
}
|
|
@ -1,283 +0,0 @@
|
|||
#include <stdio.h>
|
||||
#include "I2C_core.h"
|
||||
#include "terasic_includes.h"
|
||||
#include "mipi_camera_config.h"
|
||||
#include "mipi_bridge_config.h"
|
||||
#include "system.h"
|
||||
|
||||
#include "auto_focus.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
//EEE_IMGPROC defines
|
||||
#define EEE_IMGPROC_MSG_START ('R'<<16 | 'B'<<8 | 'B')
|
||||
|
||||
//offsets
|
||||
#define EEE_IMGPROC_STATUS 0
|
||||
#define EEE_IMGPROC_MSG 1
|
||||
#define EEE_IMGPROC_ID 2
|
||||
#define EEE_IMGPROC_BBCOL 3
|
||||
|
||||
#define EXPOSURE_INIT 0x002000
|
||||
#define EXPOSURE_STEP 0x100
|
||||
#define GAIN_INIT 0xFFF
|
||||
#define GAIN_STEP 0xFFF
|
||||
#define DEFAULT_LEVEL 3
|
||||
|
||||
#define MIPI_REG_PHYClkCtl 0x0056
|
||||
#define MIPI_REG_PHYData0Ctl 0x0058
|
||||
#define MIPI_REG_PHYData1Ctl 0x005A
|
||||
#define MIPI_REG_PHYData2Ctl 0x005C
|
||||
#define MIPI_REG_PHYData3Ctl 0x005E
|
||||
#define MIPI_REG_PHYTimDly 0x0060
|
||||
#define MIPI_REG_PHYSta 0x0062
|
||||
#define MIPI_REG_CSIStatus 0x0064
|
||||
#define MIPI_REG_CSIErrEn 0x0066
|
||||
#define MIPI_REG_MDLSynErr 0x0068
|
||||
#define MIPI_REG_FrmErrCnt 0x0080
|
||||
#define MIPI_REG_MDLErrCnt 0x0090
|
||||
|
||||
void mipi_clear_error(void){
|
||||
MipiBridgeRegWrite(MIPI_REG_CSIStatus,0x01FF); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLSynErr,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_FrmErrCnt,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLErrCnt, 0x0000); // clear error
|
||||
|
||||
MipiBridgeRegWrite(0x0082,0x00);
|
||||
MipiBridgeRegWrite(0x0084,0x00);
|
||||
MipiBridgeRegWrite(0x0086,0x00);
|
||||
MipiBridgeRegWrite(0x0088,0x00);
|
||||
MipiBridgeRegWrite(0x008A,0x00);
|
||||
MipiBridgeRegWrite(0x008C,0x00);
|
||||
MipiBridgeRegWrite(0x008E,0x00);
|
||||
MipiBridgeRegWrite(0x0090,0x00);
|
||||
}
|
||||
|
||||
void mipi_show_error_info(void){
|
||||
|
||||
alt_u16 PHY_status, SCI_status, MDLSynErr, FrmErrCnt, MDLErrCnt;
|
||||
|
||||
PHY_status = MipiBridgeRegRead(MIPI_REG_PHYSta);
|
||||
SCI_status = MipiBridgeRegRead(MIPI_REG_CSIStatus);
|
||||
MDLSynErr = MipiBridgeRegRead(MIPI_REG_MDLSynErr);
|
||||
FrmErrCnt = MipiBridgeRegRead(MIPI_REG_FrmErrCnt);
|
||||
MDLErrCnt = MipiBridgeRegRead(MIPI_REG_MDLErrCnt);
|
||||
printf("PHY_status=%xh, CSI_status=%xh, MDLSynErr=%xh, FrmErrCnt=%xh, MDLErrCnt=%xh\r\n", PHY_status, SCI_status, MDLSynErr,FrmErrCnt, MDLErrCnt);
|
||||
}
|
||||
|
||||
void mipi_show_error_info_more(void){
|
||||
printf("FrmErrCnt = %d\n",MipiBridgeRegRead(0x0080));
|
||||
printf("CRCErrCnt = %d\n",MipiBridgeRegRead(0x0082));
|
||||
printf("CorErrCnt = %d\n",MipiBridgeRegRead(0x0084));
|
||||
printf("HdrErrCnt = %d\n",MipiBridgeRegRead(0x0086));
|
||||
printf("EIDErrCnt = %d\n",MipiBridgeRegRead(0x0088));
|
||||
printf("CtlErrCnt = %d\n",MipiBridgeRegRead(0x008A));
|
||||
printf("SoTErrCnt = %d\n",MipiBridgeRegRead(0x008C));
|
||||
printf("SynErrCnt = %d\n",MipiBridgeRegRead(0x008E));
|
||||
printf("MDLErrCnt = %d\n",MipiBridgeRegRead(0x0090));
|
||||
printf("FIFOSTATUS = %d\n",MipiBridgeRegRead(0x00F8));
|
||||
printf("DataType = 0x%04x\n",MipiBridgeRegRead(0x006A));
|
||||
printf("CSIPktLen = %d\n",MipiBridgeRegRead(0x006E));
|
||||
}
|
||||
|
||||
bool MIPI_Init(void){
|
||||
bool bSuccess;
|
||||
bSuccess = oc_i2c_init_ex(I2C_OPENCORES_MIPI_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
if (!bSuccess)
|
||||
printf("failed to init MIPI- Bridge i2c\r\n");
|
||||
usleep(50*1000);
|
||||
MipiBridgeInit();
|
||||
usleep(500*1000);
|
||||
// bSuccess = oc_i2c_init_ex(I2C_OPENCORES_CAMERA_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
// if (!bSuccess)
|
||||
// printf("failed to init MIPI- Camera i2c\r\n");
|
||||
MipiCameraInit();
|
||||
MIPI_BIN_LEVEL(DEFAULT_LEVEL);
|
||||
// OV8865_FOCUS_Move_to(340);
|
||||
// oc_i2c_uninit(I2C_OPENCORES_CAMERA_BASE); // Release I2C bus , due to two I2C master shared!
|
||||
usleep(1000);
|
||||
// oc_i2c_uninit(I2C_OPENCORES_MIPI_BASE);
|
||||
return bSuccess;
|
||||
}
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);
|
||||
|
||||
printf("DE10-LITE D8M VGA Demo\n");
|
||||
printf("Imperial College EEE2 Project version\n");
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0x00);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0x00);
|
||||
|
||||
usleep(2000);
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0xFF);
|
||||
usleep(2000);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0xFF);
|
||||
|
||||
printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID));
|
||||
//printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID)); //Don't know why this doesn't work - definition is in system.h in BSP
|
||||
|
||||
|
||||
usleep(2000);
|
||||
|
||||
|
||||
// MIPI Init
|
||||
if (!MIPI_Init()){
|
||||
printf("MIPI_Init Init failed!\r\n");
|
||||
}else{
|
||||
printf("MIPI_Init Init successfully!\r\n");
|
||||
}
|
||||
|
||||
// while(1){
|
||||
mipi_clear_error();
|
||||
usleep(50*1000);
|
||||
mipi_clear_error();
|
||||
usleep(1000*1000);
|
||||
mipi_show_error_info();
|
||||
// mipi_show_error_info_more();
|
||||
printf("\n");
|
||||
// }
|
||||
|
||||
|
||||
#if 0 // focus sweep
|
||||
printf("\nFocus sweep\n");
|
||||
alt_u16 ii= 350;
|
||||
alt_u8 dir = 0;
|
||||
while(1){
|
||||
if(ii< 50) dir = 1;
|
||||
else if (ii> 1000) dir =0;
|
||||
|
||||
if(dir) ii += 20;
|
||||
else ii -= 20;
|
||||
|
||||
printf("%d\n",ii);
|
||||
OV8865_FOCUS_Move_to(ii);
|
||||
usleep(50*1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////
|
||||
alt_u16 bin_level = DEFAULT_LEVEL;
|
||||
alt_u8 manual_focus_step = 10;
|
||||
alt_u16 current_focus = 300;
|
||||
int boundingBoxColour = 0;
|
||||
alt_u32 exposureTime = EXPOSURE_INIT;
|
||||
alt_u16 gain = GAIN_INIT;
|
||||
|
||||
OV8865SetExposure(exposureTime);
|
||||
OV8865SetGain(gain);
|
||||
Focus_Init();
|
||||
while(1){
|
||||
|
||||
// touch KEY0 to trigger Auto focus
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x02){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
// touch KEY1 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x01){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0E){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
|
||||
// touch KEY1 to trigger Manual focus - step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0D){
|
||||
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
else current_focus = 0;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
|
||||
}
|
||||
|
||||
// touch KEY2 to trigger Manual focus + step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0B){
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
}
|
||||
|
||||
// touch KEY3 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x07){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
//Read messages from the image processor and print them on the terminal
|
||||
while ((IORD(0x42000,EEE_IMGPROC_STATUS)>>8) & 0xff) { //Find out if there are words to read
|
||||
int word = IORD(0x42000,EEE_IMGPROC_MSG); //Get next word from message buffer
|
||||
if (word == EEE_IMGPROC_MSG_START){ //Newline on message identifier
|
||||
printf("\n");
|
||||
}
|
||||
printf("%08x ",word);
|
||||
}
|
||||
|
||||
//Update the bounding box colour
|
||||
boundingBoxColour = ((boundingBoxColour + 1) & 0xff);
|
||||
IOWR(0x42000, EEE_IMGPROC_BBCOL, (boundingBoxColour << 8) | (0xff - boundingBoxColour));
|
||||
|
||||
//Process input commands
|
||||
int in = getchar();
|
||||
switch (in) {
|
||||
case 'e': {
|
||||
exposureTime += EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 'd': {
|
||||
exposureTime -= EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 't': {
|
||||
gain += GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'g': {
|
||||
gain -= GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'r': {
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
case 'f': {
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
}
|
||||
|
||||
|
||||
//Main loop delay
|
||||
usleep(10000);
|
||||
|
||||
};
|
||||
return 0;
|
||||
}
|
|
@ -1,302 +0,0 @@
|
|||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "I2C_core.h"
|
||||
#include "terasic_includes.h"
|
||||
#include "mipi_camera_config.h"
|
||||
#include "mipi_bridge_config.h"
|
||||
#include "system.h"
|
||||
|
||||
#include "auto_focus.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
//EEE_IMGPROC defines
|
||||
#define EEE_IMGPROC_MSG_START ('R'<<16 | 'B'<<8 | 'B')
|
||||
|
||||
//offsets
|
||||
#define EEE_IMGPROC_STATUS 0
|
||||
#define EEE_IMGPROC_MSG 1
|
||||
#define EEE_IMGPROC_ID 2
|
||||
#define EEE_IMGPROC_BBCOL 3
|
||||
|
||||
#define EXPOSURE_INIT 0x002000
|
||||
#define EXPOSURE_STEP 0x100
|
||||
#define GAIN_INIT 0xFFF
|
||||
#define GAIN_STEP 0xFFF
|
||||
#define DEFAULT_LEVEL 3
|
||||
|
||||
#define MIPI_REG_PHYClkCtl 0x0056
|
||||
#define MIPI_REG_PHYData0Ctl 0x0058
|
||||
#define MIPI_REG_PHYData1Ctl 0x005A
|
||||
#define MIPI_REG_PHYData2Ctl 0x005C
|
||||
#define MIPI_REG_PHYData3Ctl 0x005E
|
||||
#define MIPI_REG_PHYTimDly 0x0060
|
||||
#define MIPI_REG_PHYSta 0x0062
|
||||
#define MIPI_REG_CSIStatus 0x0064
|
||||
#define MIPI_REG_CSIErrEn 0x0066
|
||||
#define MIPI_REG_MDLSynErr 0x0068
|
||||
#define MIPI_REG_FrmErrCnt 0x0080
|
||||
#define MIPI_REG_MDLErrCnt 0x0090
|
||||
|
||||
void mipi_clear_error(void){
|
||||
MipiBridgeRegWrite(MIPI_REG_CSIStatus,0x01FF); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLSynErr,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_FrmErrCnt,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLErrCnt, 0x0000); // clear error
|
||||
|
||||
MipiBridgeRegWrite(0x0082,0x00);
|
||||
MipiBridgeRegWrite(0x0084,0x00);
|
||||
MipiBridgeRegWrite(0x0086,0x00);
|
||||
MipiBridgeRegWrite(0x0088,0x00);
|
||||
MipiBridgeRegWrite(0x008A,0x00);
|
||||
MipiBridgeRegWrite(0x008C,0x00);
|
||||
MipiBridgeRegWrite(0x008E,0x00);
|
||||
MipiBridgeRegWrite(0x0090,0x00);
|
||||
}
|
||||
|
||||
void mipi_show_error_info(void){
|
||||
|
||||
alt_u16 PHY_status, SCI_status, MDLSynErr, FrmErrCnt, MDLErrCnt;
|
||||
|
||||
PHY_status = MipiBridgeRegRead(MIPI_REG_PHYSta);
|
||||
SCI_status = MipiBridgeRegRead(MIPI_REG_CSIStatus);
|
||||
MDLSynErr = MipiBridgeRegRead(MIPI_REG_MDLSynErr);
|
||||
FrmErrCnt = MipiBridgeRegRead(MIPI_REG_FrmErrCnt);
|
||||
MDLErrCnt = MipiBridgeRegRead(MIPI_REG_MDLErrCnt);
|
||||
printf("PHY_status=%xh, CSI_status=%xh, MDLSynErr=%xh, FrmErrCnt=%xh, MDLErrCnt=%xh\r\n", PHY_status, SCI_status, MDLSynErr,FrmErrCnt, MDLErrCnt);
|
||||
}
|
||||
|
||||
void mipi_show_error_info_more(void){
|
||||
printf("FrmErrCnt = %d\n",MipiBridgeRegRead(0x0080));
|
||||
printf("CRCErrCnt = %d\n",MipiBridgeRegRead(0x0082));
|
||||
printf("CorErrCnt = %d\n",MipiBridgeRegRead(0x0084));
|
||||
printf("HdrErrCnt = %d\n",MipiBridgeRegRead(0x0086));
|
||||
printf("EIDErrCnt = %d\n",MipiBridgeRegRead(0x0088));
|
||||
printf("CtlErrCnt = %d\n",MipiBridgeRegRead(0x008A));
|
||||
printf("SoTErrCnt = %d\n",MipiBridgeRegRead(0x008C));
|
||||
printf("SynErrCnt = %d\n",MipiBridgeRegRead(0x008E));
|
||||
printf("MDLErrCnt = %d\n",MipiBridgeRegRead(0x0090));
|
||||
printf("FIFOSTATUS = %d\n",MipiBridgeRegRead(0x00F8));
|
||||
printf("DataType = 0x%04x\n",MipiBridgeRegRead(0x006A));
|
||||
printf("CSIPktLen = %d\n",MipiBridgeRegRead(0x006E));
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool MIPI_Init(void){
|
||||
bool bSuccess;
|
||||
|
||||
|
||||
bSuccess = oc_i2c_init_ex(I2C_OPENCORES_MIPI_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
if (!bSuccess)
|
||||
printf("failed to init MIPI- Bridge i2c\r\n");
|
||||
|
||||
usleep(50*1000);
|
||||
MipiBridgeInit();
|
||||
|
||||
usleep(500*1000);
|
||||
|
||||
// bSuccess = oc_i2c_init_ex(I2C_OPENCORES_CAMERA_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
// if (!bSuccess)
|
||||
// printf("failed to init MIPI- Camera i2c\r\n");
|
||||
|
||||
MipiCameraInit();
|
||||
MIPI_BIN_LEVEL(DEFAULT_LEVEL);
|
||||
// OV8865_FOCUS_Move_to(340);
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_CAMERA_BASE); // Release I2C bus , due to two I2C master shared!
|
||||
|
||||
|
||||
usleep(1000);
|
||||
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_MIPI_BASE);
|
||||
|
||||
return bSuccess;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);
|
||||
|
||||
printf("DE10-LITE D8M VGA Demo\n");
|
||||
printf("Imperial College EEE2 Project version\n");
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0x00);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0x00);
|
||||
|
||||
usleep(2000);
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0xFF);
|
||||
usleep(2000);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0xFF);
|
||||
|
||||
printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID));
|
||||
//printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID)); //Don't know why this doesn't work - definition is in system.h in BSP
|
||||
|
||||
|
||||
usleep(2000);
|
||||
|
||||
|
||||
// MIPI Init
|
||||
if (!MIPI_Init()){
|
||||
printf("MIPI_Init Init failed!\r\n");
|
||||
}else{
|
||||
printf("MIPI_Init Init successfully!\r\n");
|
||||
}
|
||||
|
||||
// while(1){
|
||||
mipi_clear_error();
|
||||
usleep(50*1000);
|
||||
mipi_clear_error();
|
||||
usleep(1000*1000);
|
||||
mipi_show_error_info();
|
||||
// mipi_show_error_info_more();
|
||||
printf("\n");
|
||||
// }
|
||||
|
||||
|
||||
#if 0 // focus sweep
|
||||
printf("\nFocus sweep\n");
|
||||
alt_u16 ii= 350;
|
||||
alt_u8 dir = 0;
|
||||
while(1){
|
||||
if(ii< 50) dir = 1;
|
||||
else if (ii> 1000) dir =0;
|
||||
|
||||
if(dir) ii += 20;
|
||||
else ii -= 20;
|
||||
|
||||
printf("%d\n",ii);
|
||||
OV8865_FOCUS_Move_to(ii);
|
||||
usleep(50*1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////
|
||||
alt_u16 bin_level = DEFAULT_LEVEL;
|
||||
alt_u8 manual_focus_step = 10;
|
||||
alt_u16 current_focus = 300;
|
||||
int boundingBoxColour = 0;
|
||||
alt_u32 exposureTime = EXPOSURE_INIT;
|
||||
alt_u16 gain = GAIN_INIT;
|
||||
|
||||
OV8865SetExposure(exposureTime);
|
||||
OV8865SetGain(gain);
|
||||
Focus_Init();
|
||||
while(1){
|
||||
|
||||
// touch KEY0 to trigger Auto focus
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x02){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
// touch KEY1 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x01){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0E){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
|
||||
// touch KEY1 to trigger Manual focus - step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0D){
|
||||
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
else current_focus = 0;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
|
||||
}
|
||||
|
||||
// touch KEY2 to trigger Manual focus + step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0B){
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
}
|
||||
|
||||
// touch KEY3 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x07){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
//Read messages from the image processor and print them on the terminal
|
||||
while ((IORD(0x42000,EEE_IMGPROC_STATUS)>>8) & 0xff) { //Find out if there are words to read
|
||||
int word = IORD(0x42000,EEE_IMGPROC_MSG); //Get next word from message buffer
|
||||
if (word == EEE_IMGPROC_MSG_START){ //Newline on message identifier
|
||||
printf("\n");
|
||||
}
|
||||
printf("%08x ",word);
|
||||
}
|
||||
|
||||
//Update the bounding box colour
|
||||
boundingBoxColour = ((boundingBoxColour + 1) & 0xff);
|
||||
IOWR(0x42000, EEE_IMGPROC_BBCOL, (boundingBoxColour << 8) | (0xff - boundingBoxColour));
|
||||
|
||||
//Process input commands
|
||||
int in = getchar();
|
||||
switch (in) {
|
||||
case 'e': {
|
||||
exposureTime += EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 'd': {
|
||||
exposureTime -= EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 't': {
|
||||
gain += GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'g': {
|
||||
gain -= GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'r': {
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
case 'f': {
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
}
|
||||
|
||||
|
||||
//Main loop delay
|
||||
usleep(10000);
|
||||
|
||||
};
|
||||
return 0;
|
||||
}
|
|
@ -1,301 +0,0 @@
|
|||
|
||||
|
||||
#include <stdio.h>
|
||||
#include "I2C_core.h"
|
||||
#include "terasic_includes.h"
|
||||
#include "mipi_camera_config.h"
|
||||
#include "mipi_bridge_config.h"
|
||||
|
||||
#include "auto_focus.h"
|
||||
|
||||
#include <fcntl.h>
|
||||
#include <unistd.h>
|
||||
|
||||
//EEE_IMGPROC defines
|
||||
#define EEE_IMGPROC_MSG_START ('R'<<16 | 'B'<<8 | 'B')
|
||||
|
||||
//offsets
|
||||
#define EEE_IMGPROC_STATUS 0
|
||||
#define EEE_IMGPROC_MSG 1
|
||||
#define EEE_IMGPROC_ID 2
|
||||
#define EEE_IMGPROC_BBCOL 3
|
||||
|
||||
#define EXPOSURE_INIT 0x002000
|
||||
#define EXPOSURE_STEP 0x100
|
||||
#define GAIN_INIT 0xFFF
|
||||
#define GAIN_STEP 0xFFF
|
||||
#define DEFAULT_LEVEL 3
|
||||
|
||||
#define MIPI_REG_PHYClkCtl 0x0056
|
||||
#define MIPI_REG_PHYData0Ctl 0x0058
|
||||
#define MIPI_REG_PHYData1Ctl 0x005A
|
||||
#define MIPI_REG_PHYData2Ctl 0x005C
|
||||
#define MIPI_REG_PHYData3Ctl 0x005E
|
||||
#define MIPI_REG_PHYTimDly 0x0060
|
||||
#define MIPI_REG_PHYSta 0x0062
|
||||
#define MIPI_REG_CSIStatus 0x0064
|
||||
#define MIPI_REG_CSIErrEn 0x0066
|
||||
#define MIPI_REG_MDLSynErr 0x0068
|
||||
#define MIPI_REG_FrmErrCnt 0x0080
|
||||
#define MIPI_REG_MDLErrCnt 0x0090
|
||||
|
||||
void mipi_clear_error(void){
|
||||
MipiBridgeRegWrite(MIPI_REG_CSIStatus,0x01FF); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLSynErr,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_FrmErrCnt,0x0000); // clear error
|
||||
MipiBridgeRegWrite(MIPI_REG_MDLErrCnt, 0x0000); // clear error
|
||||
|
||||
MipiBridgeRegWrite(0x0082,0x00);
|
||||
MipiBridgeRegWrite(0x0084,0x00);
|
||||
MipiBridgeRegWrite(0x0086,0x00);
|
||||
MipiBridgeRegWrite(0x0088,0x00);
|
||||
MipiBridgeRegWrite(0x008A,0x00);
|
||||
MipiBridgeRegWrite(0x008C,0x00);
|
||||
MipiBridgeRegWrite(0x008E,0x00);
|
||||
MipiBridgeRegWrite(0x0090,0x00);
|
||||
}
|
||||
|
||||
void mipi_show_error_info(void){
|
||||
|
||||
alt_u16 PHY_status, SCI_status, MDLSynErr, FrmErrCnt, MDLErrCnt;
|
||||
|
||||
PHY_status = MipiBridgeRegRead(MIPI_REG_PHYSta);
|
||||
SCI_status = MipiBridgeRegRead(MIPI_REG_CSIStatus);
|
||||
MDLSynErr = MipiBridgeRegRead(MIPI_REG_MDLSynErr);
|
||||
FrmErrCnt = MipiBridgeRegRead(MIPI_REG_FrmErrCnt);
|
||||
MDLErrCnt = MipiBridgeRegRead(MIPI_REG_MDLErrCnt);
|
||||
printf("PHY_status=%xh, CSI_status=%xh, MDLSynErr=%xh, FrmErrCnt=%xh, MDLErrCnt=%xh\r\n", PHY_status, SCI_status, MDLSynErr,FrmErrCnt, MDLErrCnt);
|
||||
}
|
||||
|
||||
void mipi_show_error_info_more(void){
|
||||
printf("FrmErrCnt = %d\n",MipiBridgeRegRead(0x0080));
|
||||
printf("CRCErrCnt = %d\n",MipiBridgeRegRead(0x0082));
|
||||
printf("CorErrCnt = %d\n",MipiBridgeRegRead(0x0084));
|
||||
printf("HdrErrCnt = %d\n",MipiBridgeRegRead(0x0086));
|
||||
printf("EIDErrCnt = %d\n",MipiBridgeRegRead(0x0088));
|
||||
printf("CtlErrCnt = %d\n",MipiBridgeRegRead(0x008A));
|
||||
printf("SoTErrCnt = %d\n",MipiBridgeRegRead(0x008C));
|
||||
printf("SynErrCnt = %d\n",MipiBridgeRegRead(0x008E));
|
||||
printf("MDLErrCnt = %d\n",MipiBridgeRegRead(0x0090));
|
||||
printf("FIFOSTATUS = %d\n",MipiBridgeRegRead(0x00F8));
|
||||
printf("DataType = 0x%04x\n",MipiBridgeRegRead(0x006A));
|
||||
printf("CSIPktLen = %d\n",MipiBridgeRegRead(0x006E));
|
||||
}
|
||||
|
||||
|
||||
|
||||
bool MIPI_Init(void){
|
||||
bool bSuccess;
|
||||
|
||||
|
||||
bSuccess = oc_i2c_init_ex(I2C_OPENCORES_MIPI_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
if (!bSuccess)
|
||||
printf("failed to init MIPI- Bridge i2c\r\n");
|
||||
|
||||
usleep(50*1000);
|
||||
MipiBridgeInit();
|
||||
|
||||
usleep(500*1000);
|
||||
|
||||
// bSuccess = oc_i2c_init_ex(I2C_OPENCORES_CAMERA_BASE, 50*1000*1000,400*1000); //I2C: 400K
|
||||
// if (!bSuccess)
|
||||
// printf("failed to init MIPI- Camera i2c\r\n");
|
||||
|
||||
MipiCameraInit();
|
||||
MIPI_BIN_LEVEL(DEFAULT_LEVEL);
|
||||
// OV8865_FOCUS_Move_to(340);
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_CAMERA_BASE); // Release I2C bus , due to two I2C master shared!
|
||||
|
||||
|
||||
usleep(1000);
|
||||
|
||||
|
||||
// oc_i2c_uninit(I2C_OPENCORES_MIPI_BASE);
|
||||
|
||||
return bSuccess;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
int main()
|
||||
{
|
||||
|
||||
fcntl(STDIN_FILENO, F_SETFL, O_NONBLOCK);
|
||||
|
||||
printf("DE10-LITE D8M VGA Demo\n");
|
||||
printf("Imperial College EEE2 Project version\n");
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0x00);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0x00);
|
||||
|
||||
usleep(2000);
|
||||
IOWR(MIPI_PWDN_N_BASE, 0x00, 0xFF);
|
||||
usleep(2000);
|
||||
IOWR(MIPI_RESET_N_BASE, 0x00, 0xFF);
|
||||
|
||||
printf("Image Processor ID: %x\n",IORD(0x42000,EEE_IMGPROC_ID));
|
||||
//printf("Image Processor ID: %x\n",IORD(EEE_IMGPROC_0_BASE,EEE_IMGPROC_ID)); //Don't know why this doesn't work - definition is in system.h in BSP
|
||||
|
||||
|
||||
usleep(2000);
|
||||
|
||||
|
||||
// MIPI Init
|
||||
if (!MIPI_Init()){
|
||||
printf("MIPI_Init Init failed!\r\n");
|
||||
}else{
|
||||
printf("MIPI_Init Init successfully!\r\n");
|
||||
}
|
||||
|
||||
// while(1){
|
||||
mipi_clear_error();
|
||||
usleep(50*1000);
|
||||
mipi_clear_error();
|
||||
usleep(1000*1000);
|
||||
mipi_show_error_info();
|
||||
// mipi_show_error_info_more();
|
||||
printf("\n");
|
||||
// }
|
||||
|
||||
|
||||
#if 0 // focus sweep
|
||||
printf("\nFocus sweep\n");
|
||||
alt_u16 ii= 350;
|
||||
alt_u8 dir = 0;
|
||||
while(1){
|
||||
if(ii< 50) dir = 1;
|
||||
else if (ii> 1000) dir =0;
|
||||
|
||||
if(dir) ii += 20;
|
||||
else ii -= 20;
|
||||
|
||||
printf("%d\n",ii);
|
||||
OV8865_FOCUS_Move_to(ii);
|
||||
usleep(50*1000);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//////////////////////////////////////////////////////////
|
||||
alt_u16 bin_level = DEFAULT_LEVEL;
|
||||
alt_u8 manual_focus_step = 10;
|
||||
alt_u16 current_focus = 300;
|
||||
int boundingBoxColour = 0;
|
||||
alt_u32 exposureTime = EXPOSURE_INIT;
|
||||
alt_u16 gain = GAIN_INIT;
|
||||
|
||||
OV8865SetExposure(exposureTime);
|
||||
OV8865SetGain(gain);
|
||||
Focus_Init();
|
||||
while(1){
|
||||
|
||||
// touch KEY0 to trigger Auto focus
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x02){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
// touch KEY1 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x03) == 0x01){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
|
||||
|
||||
#if 0
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0E){
|
||||
|
||||
current_focus = Focus_Window(320,240);
|
||||
}
|
||||
|
||||
// touch KEY1 to trigger Manual focus - step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0D){
|
||||
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
else current_focus = 0;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
|
||||
}
|
||||
|
||||
// touch KEY2 to trigger Manual focus + step
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x0B){
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
}
|
||||
|
||||
// touch KEY3 to ZOOM
|
||||
if((IORD(KEY_BASE,0)&0x0F) == 0x07){
|
||||
if(bin_level == 3 )bin_level = 1;
|
||||
else bin_level ++;
|
||||
printf("set bin level to %d\n",bin_level);
|
||||
MIPI_BIN_LEVEL(bin_level);
|
||||
usleep(500000);
|
||||
|
||||
}
|
||||
#endif
|
||||
|
||||
//Read messages from the image processor and print them on the terminal
|
||||
while ((IORD(0x42000,EEE_IMGPROC_STATUS)>>8) & 0xff) { //Find out if there are words to read
|
||||
int word = IORD(0x42000,EEE_IMGPROC_MSG); //Get next word from message buffer
|
||||
if (word == EEE_IMGPROC_MSG_START){ //Newline on message identifier
|
||||
printf("\n");
|
||||
}
|
||||
printf("%08x ",word);
|
||||
}
|
||||
|
||||
//Update the bounding box colour
|
||||
boundingBoxColour = ((boundingBoxColour + 1) & 0xff);
|
||||
IOWR(0x42000, EEE_IMGPROC_BBCOL, (boundingBoxColour << 8) | (0xff - boundingBoxColour));
|
||||
|
||||
//Process input commands
|
||||
int in = getchar();
|
||||
switch (in) {
|
||||
case 'e': {
|
||||
exposureTime += EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 'd': {
|
||||
exposureTime -= EXPOSURE_STEP;
|
||||
OV8865SetExposure(exposureTime);
|
||||
printf("\nExposure = %x ", exposureTime);
|
||||
break;}
|
||||
case 't': {
|
||||
gain += GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'g': {
|
||||
gain -= GAIN_STEP;
|
||||
OV8865SetGain(gain);
|
||||
printf("\nGain = %x ", gain);
|
||||
break;}
|
||||
case 'r': {
|
||||
current_focus += manual_focus_step;
|
||||
if(current_focus >1023) current_focus = 1023;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
case 'f': {
|
||||
if(current_focus > manual_focus_step) current_focus -= manual_focus_step;
|
||||
OV8865_FOCUS_Move_to(current_focus);
|
||||
printf("\nFocus = %x ",current_focus);
|
||||
break;}
|
||||
}
|
||||
|
||||
|
||||
//Main loop delay
|
||||
usleep(10000);
|
||||
|
||||
};
|
||||
return 0;
|
||||
}
|
Binary file not shown.
Binary file not shown.
Binary file not shown.
|
@ -1,3 +0,0 @@
|
|||
#GitProjectData
|
||||
#Tue Jun 01 14:06:14 BST 2021
|
||||
.gitdir=../../../../.git
|
Binary file not shown.
Binary file not shown.
|
@ -1,3 +0,0 @@
|
|||
#GitProjectData
|
||||
#Tue Jun 01 14:07:48 BST 2021
|
||||
.gitdir=../../../../.git
|
Binary file not shown.
|
@ -1,3 +0,0 @@
|
|||
#GitProjectData
|
||||
#Tue Jun 01 14:04:35 BST 2021
|
||||
.gitdir=../../../../.git
|
|
@ -1 +0,0 @@
|
|||
|
Binary file not shown.
|
@ -1 +0,0 @@
|
|||
|
Binary file not shown.
Binary file not shown.
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
indexer/preferenceScope=0
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
indexer/preferenceScope=0
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.cdt.debug.core.cDebug.default_source_containers=<?xml version\="1.0" encoding\="UTF-8" standalone\="no"?>\n<sourceLookupDirector>\n<sourceContainers duplicates\="false">\n<container memento\="AbsolutePath" typeId\="org.eclipse.cdt.debug.core.containerType.absolutePath"/>\n<container memento\="programRelativePath" typeId\="org.eclipse.cdt.debug.core.containerType.programRelativePath"/>\n<container memento\="<?xml version\="1.0" encoding\="UTF-8" standalone\="no"?>&\#10;<project referencedProjects\="true"/>&\#10;" typeId\="org.eclipse.cdt.debug.core.containerType.project"/>\n</sourceContainers>\n</sourceLookupDirector>\n
|
|
@ -1,3 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
properties/D8M_Camera_Test.null.1118614705/preference.org.eclipse.cdt.managedbuilder.core.configurationDataProvider.510496632=altera.tool.gnu.assembler.992693488\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.430311947\=rebuildState\\\=true\\n\naltera.nios2.linux.gcc4.292435883\=rebuildState\\\=false\\n\naltera.tool.gnu.cpp.compiler.1543692213\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.844079417\=rebuildState\\\=true\\n\npreference.org.eclipse.cdt.managedbuilder.core.configurationDataProvider.510496632\=rcState\\\=0\\nrebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.470477083\=rebuildState\\\=true\\n\norg.eclipse.cdt.build.core.settings.holder.libs.552441848\=rebuildState\\\=true\\n\naltera.tool.gnu.cpp.linker.564618922\=rebuildState\\\=false\\n\naltera.tool.gnu.c.compiler.1412563702\=rebuildState\\\=false\\n\naltera.tool.gnu.c.linker.894229324\=rebuildState\\\=false\\n\naltera.tool.gnu.archiver.1031562009\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.prefbase.toolchain.1782992537\=rebuildState\\\=true\\n\n
|
||||
properties/D8M_Camera_Test_bsp.null.1818471988/preference.org.eclipse.cdt.managedbuilder.core.configurationDataProvider.1234190122=altera.nios2.linux.gcc4.1972187429\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.440807335\=rebuildState\\\=true\\n\norg.eclipse.cdt.build.core.prefbase.toolchain.1525859819\=rebuildState\\\=true\\n\npreference.org.eclipse.cdt.managedbuilder.core.configurationDataProvider.1234190122\=rcState\\\=0\\nrebuildState\\\=false\\n\naltera.tool.gnu.assembler.917602801\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.1131241652\=rebuildState\\\=true\\n\norg.eclipse.cdt.build.core.settings.holder.libs.337058982\=rebuildState\\\=true\\n\naltera.tool.gnu.archiver.118240003\=rebuildState\\\=false\\n\naltera.tool.gnu.cpp.compiler.31029531\=rebuildState\\\=false\\n\naltera.tool.gnu.cpp.linker.1039959248\=rebuildState\\\=false\\n\norg.eclipse.cdt.build.core.settings.holder.1080074126\=rebuildState\\\=true\\n\naltera.tool.gnu.c.linker.1364287684\=rebuildState\\\=false\\n\naltera.tool.gnu.c.compiler.1406613831\=rebuildState\\\=false\\n\n
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.mylyn.cdt.ui.run.count.3_3_0=1
|
|
@ -1,5 +0,0 @@
|
|||
content_assist_disabled_computers=org.eclipse.cdt.ui.textProposalCategory\u0000org.eclipse.cdt.ui.parserProposalCategory\u0000
|
||||
eclipse.preferences.version=1
|
||||
spelling_locale_initialized=true
|
||||
useAnnotationsPrefPage=true
|
||||
useQuickDiffPrefPage=true
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
version=1
|
|
@ -1,5 +0,0 @@
|
|||
//org.eclipse.debug.core.PREFERRED_DELEGATES/org.eclipse.cdt.launch.applicationLaunchType=org.eclipse.cdt.dsf.gdb.launch.localCLaunch,debug;org.eclipse.cdt.cdi.launch.localCLaunch,run
|
||||
//org.eclipse.debug.core.PREFERRED_DELEGATES/org.eclipse.cdt.launch.attachLaunchType=org.eclipse.cdt.dsf.gdb.launch.attachCLaunch,debug
|
||||
//org.eclipse.debug.core.PREFERRED_DELEGATES/org.eclipse.cdt.launch.postmortemLaunchType=org.eclipse.cdt.dsf.gdb.launch.coreCLaunch,debug
|
||||
//org.eclipse.debug.core.PREFERRED_DELEGATES/org.eclipse.cdt.launch.remoteApplicationLaunchType=org.eclipse.rse.remotecdt.dsf.debug,debug
|
||||
eclipse.preferences.version=1
|
|
@ -1,3 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.debug.ui.PREF_LAUNCH_PERSPECTIVES=<?xml version\="1.0" encoding\="UTF-8" standalone\="no"?>\n<launchPerspectives/>\n
|
||||
preferredTargets=org.eclipse.cdt.debug.ui.toggleCBreakpointTarget\:org.eclipse.cdt.debug.ui.toggleCBreakpointTarget|
|
|
@ -1,2 +0,0 @@
|
|||
GitRepositoriesView.GitDirectories=/home/ad3919/nfshome/EE2Rover/.git\:
|
||||
eclipse.preferences.version=1
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
mylyn.attention.migrated=true
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.mylyn.monitor.activity.tracking.enabled.checked=true
|
|
@ -1,3 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.mylyn.tasks.ui.filters.nonmatching=true
|
||||
org.eclipse.mylyn.tasks.ui.filters.nonmatching.encouraged=true
|
|
@ -1,3 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.rse.systemtype.local.systemType.defaultUserId=ad3919
|
||||
useridperkey=ee-mill2.Local\=ad3919;
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.rse.preferences.order.connections=ee-mill2.Local
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
pref_first_startup=false
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
org.eclipse.team.ui.first_time=false
|
|
@ -1,2 +0,0 @@
|
|||
eclipse.preferences.version=1
|
||||
overviewRuler_migration=migrated_3.1
|
|
@ -1,6 +0,0 @@
|
|||
PROBLEMS_FILTERS_MIGRATE=true
|
||||
TASKS_FILTERS_MIGRATE=true
|
||||
eclipse.preferences.version=1
|
||||
platformState=1622552591073
|
||||
quickStart=false
|
||||
tipsAndTricks=true
|
|
@ -1,2 +0,0 @@
|
|||
ENABLED_DECORATORS=com.altera.sbtgui.project.decorator.bsp\:true,com.altera.sbtgui.project.nios2builddecorator\:true,org.eclipse.cdt.ui.indexedFiles\:false,org.eclipse.cdt.managedbuilder.ui.excludedFile\:true,org.eclipse.cdt.managedbuilder.ui.includeFolder\:true,org.eclipse.cdt.internal.ui.CustomBuildSettingsDecorator\:true,org.eclipse.egit.ui.internal.decorators.GitLightweightDecorator\:true,org.eclipse.linuxtools.tmf.ui.trace_folder.decorator\:true,org.eclipse.linuxtools.tmf.ui.experiment_folder.decorator\:true,org.eclipse.linuxtools.tmf.ui.linked_trace.decorator\:true,org.eclipse.mylyn.context.ui.decorator.interest\:true,org.eclipse.mylyn.tasks.ui.decorators.task\:true,org.eclipse.mylyn.team.ui.changeset.decorator\:true,org.eclipse.rse.core.virtualobject.decorator\:true,org.eclipse.rse.core.binary.executable.decorator\:true,org.eclipse.rse.core.script.executable.decorator\:true,org.eclipse.rse.core.java.executable.decorator\:true,org.eclipse.rse.core.library.decorator\:true,org.eclipse.rse.core.link.decorator\:true,org.eclipse.rse.subsystems.error.decorator\:true,org.eclipse.team.cvs.ui.decorator\:true,org.eclipse.ui.LinkedResourceDecorator\:true,org.eclipse.ui.SymlinkDecorator\:true,org.eclipse.ui.VirtualResourceDecorator\:true,org.eclipse.ui.ContentTypeDecorator\:true,org.eclipse.ui.ResourceFilterDecorator\:false,
|
||||
eclipse.preferences.version=1
|
File diff suppressed because one or more lines are too long
|
@ -1,27 +0,0 @@
|
|||
<?xml version="1.0" encoding="UTF-8" standalone="no"?>
|
||||
<launchHistory>
|
||||
<launchGroup id="org.eclipse.debug.ui.launchGroup.profilee">
|
||||
<mruHistory/>
|
||||
<favorites/>
|
||||
</launchGroup>
|
||||
<launchGroup id="org.eclipse.debug.ui.launchGroup.debug">
|
||||
<mruHistory>
|
||||
<launch memento="<?xml version="1.0" encoding="UTF-8" standalone="no"?> <launchConfiguration local="true" path="D8M_Camera_Test Nios II Hardware configuration"/> "/>
|
||||
</mruHistory>
|
||||
<favorites/>
|
||||
</launchGroup>
|
||||
<launchGroup id="org.eclipse.debug.ui.launchGroup.profile">
|
||||
<mruHistory/>
|
||||
<favorites/>
|
||||
</launchGroup>
|
||||
<launchGroup id="org.eclipse.ui.externaltools.launchGroup">
|
||||
<mruHistory/>
|
||||
<favorites/>
|
||||
</launchGroup>
|
||||
<launchGroup id="org.eclipse.debug.ui.launchGroup.run">
|
||||
<mruHistory>
|
||||
<launch memento="<?xml version="1.0" encoding="UTF-8" standalone="no"?> <launchConfiguration local="true" path="D8M_Camera_Test Nios II Hardware configuration"/> "/>
|
||||
</mruHistory>
|
||||
<favorites/>
|
||||
</launchGroup>
|
||||
</launchHistory>
|
File diff suppressed because it is too large
Load diff
Binary file not shown.
Some files were not shown because too many files have changed in this diff Show more
Loading…
Reference in a new issue