Skip to content

Commit

Permalink
Merge pull request #362 from gergelytakacs/Sampling_UNO_R4
Browse files Browse the repository at this point in the history
Sampling uno r4
  • Loading branch information
gergelytakacs authored Oct 10, 2023
2 parents e13f8af + 967b84c commit a561961
Show file tree
Hide file tree
Showing 31 changed files with 824 additions and 582 deletions.
6 changes: 3 additions & 3 deletions Octave/examples/MagnetoShield/MagnetoShield_Speed_Test.m
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
% "arduino" package (see pkg) then the script loads it. Although it is possible to
% override default I2C speeds, tests show no improvement with increased
% I2C communication speeds. AVR-based Arduinos, such as the UNO will
% provide the same speed, as the architecture and clock speeed is
% provide the same speed, as the architecture and clock speed is
% identical in all of them. Due or other non-AVR boards compatible with
% the MagnetoShield are not supported. The script just tests reading the
% analog input and sending data to the I2C bus without attempting feedback
Expand All @@ -22,9 +22,9 @@
% project is available at:
% https://github.com/gergelytakacs/AutomationShield/wiki/Publications
%
% Created by: Gergely Takács
% Created by: Gergely Tak�cs
% Created on: 29.10.2020
% Last updated by: Gergely Takács
% Last updated by: Gergely Tak�cs
% Last update on: 29.10.2020
% Tested on: Arduino Uno

Expand Down
2 changes: 1 addition & 1 deletion examples/AeroShield/AeroShield_EMPC/AeroShield_EMPC.ino
Original file line number Diff line number Diff line change
Expand Up @@ -68,7 +68,7 @@ static float u_opt[MPT_RANGE]; // predicted inputs
extern struct mpc_ctl ctl; // Object representing presets for MPC controller

void setup() {
Serial.begin(250000); //--Initialize serial communication
Serial.begin(115200); //--Initialize serial communication
AeroShield.begin(); //--Initialize AeroShield
delay(1000);
AeroShield.calibrate(); // Calibrate AeroShield board + store the 0° value of the pendulum
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ bool flag = false;
bool realTimeViolation = false;
int k;
void setup() {
Serial.begin(250000);
Serial.begin(115200);
AeroShield.begin();
AeroShield.calibrate();
Serial.println("y, u"); //--Print header
Expand Down
2 changes: 1 addition & 1 deletion examples/AeroShield/AeroShield_LQI/AeroShield_LQI.ino
Original file line number Diff line number Diff line change
Expand Up @@ -49,7 +49,7 @@ BLA::Matrix<1, 3> K = {-0.0376, 0.3523, 0.1337}; //--LQ gain with i
BLA::Matrix<3, 1> Xr = {0, 0, 0}; //--Initial state reference

void setup() {
Serial.begin(250000); //--Initialize serial communication # 2 Mbaud
Serial.begin(115200); //--Initialize serial communication # 2 Mbaud
AeroShield.begin(); //--Initialize MotoShield
delay(1000);
AeroShield.calibrate(); // Calibrate AeroShield board + store the 0° value of the pendulum
Expand Down
4 changes: 2 additions & 2 deletions examples/AeroShield/AeroShield_PID/AeroShield_PID.ino
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@
#define TI 0.55 // PID Ti constant
#define TD 0.25 // PID Td constant

unsigned long Ts = 3; // Sampling period in milliseconds
unsigned long Ts = 5; // Sampling period in milliseconds
unsigned long k = 0; // Sample index
bool nextStep = false; // Flag for step function
bool realTimeViolation = false; // Flag for real-time sampling violation
Expand All @@ -41,7 +41,7 @@ float y = 0.0; // Output (Current pendulum angle)
float u = 0.0; // Input (motor power)

void setup() { // Setup - runs only once
Serial.begin(2000000); // Begin serial communication
Serial.begin(115200); // Begin serial communication
AeroShield.begin(); // Initialise AeroShield board
AeroShield.calibrate(); // Calibrate AeroShield board + store the 0° value of the pendulum
Sampling.period(Ts * 1000); // Set sampling period in milliseconds
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ float powerSpan = 6; // Span +/- from stabilised value of power [
#endif

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

FloatShield.begin(); // Initialise FloatShield board
FloatShield.calibrate(); // Calibrate FloatShield board
Expand Down
2 changes: 1 addition & 1 deletion examples/FloatShield/FloatShield_LQ/FloatShield_LQ.ino
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ BLA::Matrix<4, 1> X = {0, 0, 0, 0}; // Estimated
BLA::Matrix<4, 1> Xr = {0, 0, 0, 0}; // Reference state vector

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

FloatShield.begin(); // Initialise FloatShield board
FloatShield.calibrate(); // Calibrate FloatShield board
Expand Down
2 changes: 1 addition & 1 deletion examples/FloatShield/FloatShield_MPC/FloatShield_MPC.ino
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ float Xr[4] = {0, 0, 0, 0}; // Reference state vector
extern struct mpc_ctl ctl; // Object representing presets for MPC controller

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

FloatShield.begin(); // Initialise FloatShield board
FloatShield.calibrate(); // Calibrate FloatShield board
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -27,7 +27,7 @@ unsigned long Ts = 25; // Sampling period in milliseconds
bool nextStep = false; // Flag for step function

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

FloatShield.begin(); // Initialise FloatShield
FloatShield.calibrate(); // Calibrate FloatShield
Expand Down
2 changes: 1 addition & 1 deletion examples/FloatShield/FloatShield_PID/FloatShield_PID.ino
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,7 @@ int i = 0; // Section counter
#endif

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

FloatShield.begin(); // Initialise FloatShield board
FloatShield.calibrate(); // Calibrate FloatShield board
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ static float u_opt[MPT_RANGE]; // predicted inputs
extern struct mpc_ctl ctl; // Object representing presets for MPC controller

void setup() { // Setup - runs only once
Serial.begin(250000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

MagnetoShield.begin(); // Initialize MagnetoShield device
MagnetoShield.calibration(); // Calibrate MagnetoShield device
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -56,6 +56,8 @@ int wP=(int)wPP*100; // For (pseudo)-random generator
unsigned long Ts = 5000; // Sampling in microseconds
#elif ARDUINO_ARCH_SAM
unsigned long Ts = 3250; // Sampling in microseconds
#elif ARDUINO_ARCH_RENESAS_UNO
unsigned long Ts = 5000; // Sampling in microseconds
#endif

void setup() {
Expand All @@ -64,6 +66,8 @@ void setup() {
Serial.begin(2000000); // Initialize serial, maximum for AVR given by hardware
#elif ARDUINO_ARCH_SAM
Serial.begin(250000); // Initialize serial, maximum for Due (baud mismatch issues)
#elif ARDUINO_ARCH_RENESAS_UNO
Serial.begin(115200); // Initialize serial, maximum for UNO R4 (serial communication limitations)
#endif

// Initialize and calibrate board
Expand Down
13 changes: 9 additions & 4 deletions examples/MagnetoShield/MagnetoShield_LQ/MagnetoShield_LQ.ino
Original file line number Diff line number Diff line change
Expand Up @@ -53,13 +53,16 @@ float u0 = 4.6234; // [V] Linearization point based on the expe
int i = 0; // Section counter

#if ARDUINO_ARCH_AVR
float Ts = 5; // Sampling in microseconds, lower limit near 5 ms
float Ts = 5; // Sampling in microseconds, lower limit near 5 ms
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_SAMD
float Ts = 5; // Sampling in microseconds
float Ts = 5; // Sampling in microseconds
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_SAM
float Ts = 5; // Sampling in microseconds, lower limit 1.3 ms
float Ts = 5; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_RENESAS_UNO
float Ts = 5; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
#endif

Expand All @@ -85,8 +88,10 @@ void setup() {
AutomationShield.print("Kalman filter cannot be used with this architecture! Set USE_DIFFERENTIATION to 1 and USE_KALMAN_FILTER to 0 or use Aduino DUE!");
return 0;
#endif
#elif ARDUINO_ARCH_SAM
#elif ARDUINO_ARCH_SAM
Serial.begin(250000); // Initialize serial, maximum for Due (baud mismatch issues)
#elif ARDUINO_ARCH_RENESAS_UNO
Serial.begin(115200); // Initialize serial, maximum for UNO R4 (serial communication limitations)
#endif

// Initialize and calibrate board
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -58,6 +58,9 @@ float u = 0.0; // [V] Input
#elif ARDUINO_ARCH_SAM
unsigned long Ts = 5000; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_RENESAS_UNO
float Ts = 5; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
#endif

void setup() {
Expand All @@ -66,6 +69,8 @@ void setup() {
Serial.begin(2000000); // Initialize serial, maximum for AVR given by hardware
#elif ARDUINO_ARCH_SAM
Serial.begin(250000); // Initialize serial, maximum for Due (baud mismatch issues)
#elif ARDUINO_ARCH_RENESAS_UNO
Serial.begin(115200); // Initialize serial, maximum for UNO R4 (serial communication limitations)
#endif

// Initialize and calibrate board
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -59,7 +59,10 @@ float Ts = 5; // Sampling in microseconds
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_SAM
float Ts = 4; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
int T = 1000; // Experiment section length (steps)
#elif ARDUINO_ARCH_RENESAS_UNO
float Ts = 5; // Sampling in microseconds, lower limit 1.3 ms
int T = 1000; // Experiment section length (steps)
#endif

#if USE_KALMAN_FILTER && ARDUINO_ARCH_SAM
Expand All @@ -86,6 +89,8 @@ void setup() {
#endif
#elif ARDUINO_ARCH_SAM
Serial.begin(250000); // Initialize serial, maximum for Due (baud mismatch issues)
#elif ARDUINO_ARCH_RENESAS_UNO
Serial.begin(115200); // Initialize serial, maximum for UNO R4 (serial comunication limitations)

Check failure on line 93 in examples/MagnetoShield/MagnetoShield_PolePlacement/MagnetoShield_PolePlacement.ino

View workflow job for this annotation

GitHub Actions / spellcheck

comunication ==> communication

Check failure on line 93 in examples/MagnetoShield/MagnetoShield_PolePlacement/MagnetoShield_PolePlacement.ino

View workflow job for this annotation

GitHub Actions / spellcheck

comunication ==> communication

Check failure on line 93 in examples/MagnetoShield/MagnetoShield_PolePlacement/MagnetoShield_PolePlacement.ino

View workflow job for this annotation

GitHub Actions / spellcheck

comunication ==> communication

Check failure on line 93 in examples/MagnetoShield/MagnetoShield_PolePlacement/MagnetoShield_PolePlacement.ino

View workflow job for this annotation

GitHub Actions / spellcheck

comunication ==> communication
#endif

// Initialize and calibrate board
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ int T = 300; // Section length
int i = 0; // Section counter

void setup() {
Serial.begin(2000000); // Initialize serial
Serial.begin(115200); // Initialize serial

// Initialize and calibrate board
PressureShield.begin(); // Define hardware pins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@ BLA::Matrix<3, 1> X = {0, 0, 0}; // Estimated state
BLA::Matrix<3, 1> Xr = {0, 0, 0}; // Reference state vector

void setup() { // Setup - runs only once
Serial.begin(2000000); // Begin serial communication
Serial.begin(115200); // Begin serial communication

PressureShield.begin(); // Initialise PressureShield board
PressureShield.calibration(); // Calibrate PressureShield board
Expand Down
2 changes: 1 addition & 1 deletion examples/TugShield/TugShield_PID/TugShield_PID.ino
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,7 @@ float u ; // Input
#define TD 0.0 // PID Td

void setup() {
Serial.begin(250000); // Initialize serial
Serial.begin(115200); // Initialize serial

// Initialize and calibrate board
TugShield.begin(); // Define hardware pins
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -515,7 +515,7 @@ if (val == 73) { //I -> Provisional I2C
// no declaration for the moment : wait for encoder mode
while (Serial.available() == 0) {}; // Waiting char
int mode = Serial.read() - 48; // Read mode 1 ou 2 (1 counting only rising of chA, 2 counting rising and falling)
if (mode == 4) { // mode 4x : 2 cases : chA=pin2 / chB=pin3 or chA=pin3/chB=pin2 [Uno retriction]
if (mode == 4) { // mode 4x : 2 cases : chA=pin2 / chB=pin3 or chA=pin3/chB=pin2 [Uno restriction]
pinMode(corresp[encoder_int2], INPUT); // set interrupt number as input
} else {
pinMode(encoder_int2, INPUT); // set pin as input
Expand Down
10 changes: 2 additions & 8 deletions src/AeroShield.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -12,30 +12,24 @@
Attribution-NonCommercial 4.0 International License.
Created by Peter Tibenský, Erik Mikuláš and Ján Boldocký
Last update: 09.06.2023
Last update: 03.10.2023
*/

#include "AeroShield.h" // Include header file

// Initializes hardware pins
float AeroClass::begin(void){ // Board initialisation
#ifdef ARDUINO_ARCH_AVR // For AVR architecture boards
#if defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_SAMD) || defined(ARDUINO_ARCH_RENESAS_UNO) // For AVR, SAMD, Renesas architecture boards
Wire.begin(); // Use Wire object
as5600.setWirePtr(&Wire);
#elif ARDUINO_ARCH_SAM // For SAM architecture boards
Wire1.begin(); // Use Wire1 object
as5600.setWirePtr(&Wire1);
#elif ARDUINO_ARCH_SAMD // For SAMD architecture boards
Wire.begin(); // Use Wire object
as5600.setWirePtr(&Wire);
#endif


as5600.begin();
bool isDetected = as5600.detectMagnet();
//pinMode(AERO_UPIN, OUTPUT); // Actuator pin
//pinMode(AERO_RPIN, INPUT);
//pinMode(AERO_VOLTAGE_SENSOR_PIN, INPUT);
if(isDetected == 0){ // If magnet not detected go on
while(1){ // Go forever until magnet detected
if(isDetected == 1){ // If magnet detected
Expand Down
4 changes: 2 additions & 2 deletions src/AutomationShield.h
Original file line number Diff line number Diff line change
Expand Up @@ -29,7 +29,7 @@
#ifdef ARDUINO_ARCH_AVR // Chip uses 10-bit ADC

#define ADCREF 1023.0 // 10-bit resolution for AD converter
#elif ARDUINO_ARCH_SAMD || ARDUINO_ARCH_SAM // Chip uses 12-bit ADC
#elif ARDUINO_ARCH_SAMD || ARDUINO_ARCH_SAM || ARDUINO_ARCH_RENESAS_UNO // Chip uses 12-bit ADC
#define ADCREF 4095.0 // 12-bit resolution for AD converter
#endif

Expand All @@ -53,7 +53,7 @@
float quality(float, char *method); // Quality metric for feedback control input

// Printing functions
void serialPrint(const char *str); // Should be renamed to diagnostic printLowHigh
void serialPrint(const char *str); // Should be renamed to diagnostic printLowHigh
void print(float, float, float);
void printLowHigh(char *named, float low, float high, char *unit, short int precision); // Prints a single line for range measurements in an ordered form
void printSeparator(char); // Prints a line of dashes, 60 characters wide, then a new line.
Expand Down
13 changes: 2 additions & 11 deletions src/FloatShield.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -39,7 +39,7 @@ void FloatClass::begin(void) { // Board ini
#elif ARDUINO_ARCH_SAM // For SAM architecture boards
analogReadResolution(12);
Wire1.begin(); // Use Wire1 object
#elif ARDUINO_ARCH_SAMD // For SAMD architecture boards
#elif ARDUINO_ARCH_SAMD || ARDUINO_ARCH_RENESAS_UNO // For SAMD and RA4M1 architecture boards
analogReadResolution(12);
Wire.begin(); // Use Wire object
#endif
Expand Down Expand Up @@ -94,7 +94,7 @@ void FloatClass::calibrate(void) { // Board calibration

#if SHIELDRELEASE == 4
void FloatClass::dacWrite(uint16_t DAClevel){ // 16 bits in the form (0,0,0,0,D11,D10,D9,D8,D7,D6,D5,D4,D3,D2,D1,D0)
#ifdef ARDUINO_ARCH_AVR
#if (defined(ARDUINO_ARCH_AVR) || defined(ARDUINO_ARCH_RENESAS_UNO) || defined(ARDUINO_ARCH_SAMD))
Wire.beginTransmission(MCP4725); //addressing
Wire.write(0x40); // write dac(DAC and EEPROM is 0x60)
uint8_t firstbyte=(DAClevel>>4); //(0,0,0,0,0,0,0,0,D11,D10,D9,D8,D7,D6,D5,D4) of which only the 8 LSB's survive
Expand All @@ -112,15 +112,6 @@ void FloatClass::dacWrite(uint16_t DAClevel){ // 16 bits in the form (0,0,0,0,D1
Wire1.write(firstbyte); //first 8 MSB's
Wire1.write(secndbyte); //last 4 LSB's
Wire1.endTransmission();
#elif ARDUINO_ARCH_SAMD
Wire.beginTransmission(MCP4725); //addressing
Wire.write(0x40); // write dac(DAC and EEPROM is 0x60)
uint8_t firstbyte=(DAClevel>>4); //(0,0,0,0,0,0,0,0,D11,D10,D9,D8,D7,D6,D5,D4) of which only the 8 LSB's survive
DAClevel = DAClevel << 12; //(D3,D2,D1,D0,0,0,0,0,0,0,0,0,0,0,0,0)
uint8_t secndbyte=(DAClevel>>8); //(0,0,0,0,0,0,0,0,D3,D2,D1,D0,0,0,0,0) of which only the 8 LSB's survive.
Wire.write(firstbyte); //first 8 MSB's
Wire.write(secndbyte); //last 4 LSB's
Wire.endTransmission();
#endif
}

Expand Down
3 changes: 3 additions & 0 deletions src/LinkShield.h
Original file line number Diff line number Diff line change
Expand Up @@ -68,6 +68,9 @@ void LinkClass::begin() {
#elif ARDUINO_ARCH_SAMD
//analogReadResolution(12);
Wire.begin(); // Initialize I2C communication
#elif ARDUINO_ARCH_RENESAS_UNO
Wire.begin(); // Starts the "Wire" library for I2C
analogReference(AR_EXTERNAL); // Set reference voltage
#endif

LinkShield.ADXL_POWER_CTL();
Expand Down
Loading

0 comments on commit a561961

Please sign in to comment.