Skip to content
Snippets Groups Projects
Verified Commit 32c34d7a authored by Thomas Lambert's avatar Thomas Lambert :helicopter:
Browse files

refact: split into multiple files

parent 6edd58f3
No related branches found
No related tags found
No related merge requests found
...@@ -22,6 +22,7 @@ to [Semantic Versioning][sem_ver]. ...@@ -22,6 +22,7 @@ to [Semantic Versioning][sem_ver].
- **Logging**: Output desired frequency as well - **Logging**: Output desired frequency as well
- **All**: Various refactoring and style improvements - **All**: Various refactoring and style improvements
- **All**: Use more precise types to limit RAM - **All**: Use more precise types to limit RAM
- **Refactor**: Split the code into different files
### Deprecated ### Deprecated
......
...@@ -24,6 +24,8 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller ...@@ -24,6 +24,8 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
Macros (for pins and fixed components only!) Macros (for pins and fixed components only!)
*******************************************************************************/ *******************************************************************************/
#define BAUD_RATE 115200 // baud rate for serial
// Pins // Pins
#define ESC1_PIN 10 // ESC Front motor #define ESC1_PIN 10 // ESC Front motor
#define ESC2_PIN 9 // ESC Aft motor #define ESC2_PIN 9 // ESC Aft motor
...@@ -45,7 +47,7 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller ...@@ -45,7 +47,7 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
#define DIV_RES2 6800.0 // Resistance of R2 in the voltage dividers #define DIV_RES2 6800.0 // Resistance of R2 in the voltage dividers
#define SEN0098_VCC 5 // Supply voltage of the current sensors #define SEN0098_VCC 5 // Supply voltage of the current sensors
#define SEN0098_SENSI 20.0 // [FIXME] VERIFY! #define SEN0098_SENSI 40.0 // Chip ACS758LCB-050B-PFF-T
#define SEN0098_VIOUT 0.12 // [FIXME] VERIFY! #define SEN0098_VIOUT 0.12 // [FIXME] VERIFY!
#define SEN0098_OFFSET 0.007 // [FIXME] VERIFY! #define SEN0098_OFFSET 0.007 // [FIXME] VERIFY!
...@@ -56,7 +58,7 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller ...@@ -56,7 +58,7 @@ Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
#define ENC_PRECISION 4096 // 12-Bits encoders (nb of points per rot) #define ENC_PRECISION 4096 // 12-Bits encoders (nb of points per rot)
#define ENC_ORIENT {1, -1, 1, -1} // Encoder orientation #define ENC_ORIENT {1, -1, 1, -1} // Encoder orientation
#define MAX_WING_POS {222.1, 117.77, 117, 117} // Maximum wing angle (returned by encoder value) #define MAX_WING_POS {222.1, 117.77, 117, 117} // Maximum wing angle (returned by encoder value)
#define TRUE_MAX_ANGLE 37.9 // Maximum wing angle (measured on setup) #define TRUE_MAX_ANGLE 38.07 // Maximum wing angle (measured on setup)
/******************************************************************************* /*******************************************************************************
Globals (for things that I can change manually) Globals (for things that I can change manually)
...@@ -73,7 +75,6 @@ const uint8_t gMIN_ESC_VAL = 40; // Min value for ESC to start motor (trial-er ...@@ -73,7 +75,6 @@ const uint8_t gMIN_ESC_VAL = 40; // Min value for ESC to start motor (trial-er
const uint8_t gCSN_PINS[] = CSN_PINS; // Encoder Chip Select pins const uint8_t gCSN_PINS[] = CSN_PINS; // Encoder Chip Select pins
const int8_t gENC_ORIENT[] = ENC_ORIENT; // Encoder orientation const int8_t gENC_ORIENT[] = ENC_ORIENT; // Encoder orientation
const uint16_t gMAX_WING_POS[] = MAX_WING_POS; // Encoder maximum recorder position
const float gCUR_FACT = SEN0098_SENSI / 1000.0; // Factor for current measurement const float gCUR_FACT = SEN0098_SENSI / 1000.0; // Factor for current measurement
const float gCUR_QOV = SEN0098_VIOUT * SEN0098_VCC; // [FIXME] Verify const float gCUR_QOV = SEN0098_VIOUT * SEN0098_VCC; // [FIXME] Verify
...@@ -83,15 +84,14 @@ Servo gEsc2; // ESC for aft motor ...@@ -83,15 +84,14 @@ Servo gEsc2; // ESC for aft motor
uint8_t gEsc_val = 0; // ESC angle (to use with the Servo library) [0-180] uint8_t gEsc_val = 0; // ESC angle (to use with the Servo library) [0-180]
String gMode; // Mode of operation String gMode; // Mode of operation
uint16_t max_wing_pos[4]; // Encoder maximum recorder position uint16_t max_wing_pos[] = MAX_WING_POS; // Encoder maximum recorder position
/******************************************************************************* /*******************************************************************************
ARDUINO SETUP ARDUINO SETUP
*******************************************************************************/ *******************************************************************************/
void setup() { void setup() {
//Serial.begin(9600); //[DEBUG]: For debugging only Serial.begin(BAUD_RATE);
Serial.begin(115200); // Need for good precision
// Init ESCs // Init ESCs
Serial.print("[INFO]: Attaching ESCs ... "); Serial.print("[INFO]: Attaching ESCs ... ");
...@@ -116,17 +116,21 @@ void setup() { ...@@ -116,17 +116,21 @@ void setup() {
int switch_state = digitalRead(SWITCH_PIN); int switch_state = digitalRead(SWITCH_PIN);
if (switch_state == LOW) { if (switch_state == LOW) {
gMode = "MANUAL"; gMode = "MANUAL";
Serial.println("[WARN]: Control motors using potentiometer"); Serial.println("[WARNING]: Control motors using potentiometer");
} else { } else {
gEsc1.write(0); // Must be initialized at 0 otherwise will not start gEsc1.write(0); // Must be initialized at 0 otherwise will not start
gEsc2.write(0); gEsc2.write(0);
gMode = "SERIAL"; gMode = "SERIAL";
Serial.println("[WARN]: Control motors using serial"); Serial.println("[WARNING]: Control motors using serial");
gEsc_val = SetupSerial(); gEsc_val = SetupSerial();
} }
// Calibrate angle sensors
// SetupCalibration();
Serial.println("[INFO]: Setup OK, starting now..."); Serial.println("[INFO]: Setup OK, starting now...");
delay(1000); // Ensure all is properly initialized delay(1000); // Ensure all is properly initialized
} }
...@@ -216,27 +220,6 @@ float SetupSerial() { ...@@ -216,27 +220,6 @@ float SetupSerial() {
} }
// Converts frequence to ESC angle to use with Servo library
int FreqToEsc(float freq) {
// Need to scale times 100 so we can have better precision
int esc_val = freq * (180.0 / RpmToFreq(gMAX_RPM));
if (esc_val < gMIN_ESC_VAL) {
esc_val = gMIN_ESC_VAL;
} else if (esc_val > gMAX_ESC_VAL) {
esc_val = gMAX_ESC_VAL;
}
return esc_val;
}
// Converts RPM to Flapping frequency
float RpmToFreq(int rpm) {
return rpm * GEAR_RATIO / 60.0;
}
// Gracefully stops the motor in serial mode // Gracefully stops the motor in serial mode
void StopMotor(int old_esc_val) { void StopMotor(int old_esc_val) {
...@@ -259,26 +242,6 @@ void StopMotor(int old_esc_val) { ...@@ -259,26 +242,6 @@ void StopMotor(int old_esc_val) {
} }
//Read 12-bit rotary encoder (RobinL modified by linarism on forum.arduino.cc)
unsigned int ReadSensor(uint8_t csn, int8_t orient) {
unsigned int ret = 0;
digitalWrite(csn, LOW);
delayMicroseconds(1); //Waiting for Tclkfe
//Passing 12 times, from 0 to 11
for (int x = 0; x < 12; x++) {
digitalWrite(CLK_PIN, LOW);
delayMicroseconds(1); //Tclk/2
digitalWrite(CLK_PIN, HIGH);
delayMicroseconds(1); //Tdo valid, like Tclk/2
ret = (ret << 1) | digitalRead(DO_PIN); //shift all the entering data to the left and past the pin state to it. 1e bit is MSB
}
digitalWrite(csn, HIGH); //deselects the encoder from reading
return (1-orient)/2 * ENC_PRECISION + orient*ret;
}
// Output data to use with serial-studio // Output data to use with serial-studio
void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[], float psu_vol[], float psu_cur[]) { void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[], float psu_vol[], float psu_cur[]) {
...@@ -297,7 +260,7 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[ ...@@ -297,7 +260,7 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[
Serial.print(freq); Serial.print(freq);
for (int i = 0; i < sizeof(gCSN_PINS); i++) { for (int i = 0; i < sizeof(gCSN_PINS); i++) {
Serial.print(","); Serial.print(",");
Serial.print(PosToDeg(wing_angles[i])-gMAX_WING_POS[i] + TRUE_MAX_ANGLE); Serial.print(PosToDeg(wing_angles[i])-max_wing_pos[i] + TRUE_MAX_ANGLE);
} }
for (int i = 0; i < sizeof(psu_vol); i++) { for (int i = 0; i < sizeof(psu_vol); i++) {
Serial.print(","); Serial.print(",");
...@@ -307,34 +270,3 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[ ...@@ -307,34 +270,3 @@ void SerialPrint(String mode, int potent, int esc_val, unsigned int wing_angles[
} }
Serial.println("*/"); // End of data stream Serial.println("*/"); // End of data stream
} }
// Get the tension and current of a PSU
void GetPsu(byte vol_pin, byte cur_pin, float &vol, float &cur) {
vol = GetTension(vol_pin);
cur = GetCurrent(cur_pin);
}
// Measure current consumed by module
// [FIXME] Check properly
float GetCurrent(byte cur_pin) {
float volt_raw = (5.0 / 1023.0) * analogRead(cur_pin);
float volt = volt_raw * -gCUR_QOV + SEN0098_OFFSET; // Trimming value to make current equal to 0 when no current
return volt / gCUR_FACT; // Actual current
}
// Measure the tension provided by the PSU
float GetTension(byte vol_pin) {
float vol_raw = analogRead(vol_pin) * (5.0 / 1023.0);
return vol_raw * (DIV_RES1 + DIV_RES2) / (DIV_RES2);
}
// Convert encoder position to degree
float PosToDeg(unsigned int pos){
return pos * 360.0 / ENC_PRECISION;
}
/*******************************************************************************
Sensors
Functions for sensors and acquisition.
--------------------------------------------------------------------------------
(c) Copyright 2022 University of Liege
Author: Thomas Lambert <t.lambert@uliege.be>
ULiege - Aeroelasticity and Experimental Aerodynamics
MIT License
Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
*******************************************************************************/
//Read 12-bit rotary encoder (RobinL modified by linarism on forum.arduino.cc)
unsigned int ReadSensor(uint8_t csn, int8_t orient) {
unsigned int ret = 0;
digitalWrite(csn, LOW);
delayMicroseconds(1); //Waiting for Tclkfe
//Passing 12 times, from 0 to 11
for (int x = 0; x < 12; x++) {
digitalWrite(CLK_PIN, LOW);
delayMicroseconds(1); //Tclk/2
digitalWrite(CLK_PIN, HIGH);
delayMicroseconds(1); //Tdo valid, like Tclk/2
ret = (ret << 1) | digitalRead(DO_PIN); //shift all the entering data to the left and past the pin state to it. 1e bit is MSB
}
digitalWrite(csn, HIGH); //deselects the encoder from reading
return (1-orient)/2 * ENC_PRECISION + orient*ret;
}
// Get the tension and current of a PSU
void GetPsu(byte vol_pin, byte cur_pin, float &vol, float &cur) {
vol = GetTension(vol_pin);
cur = GetCurrent(cur_pin);
}
// Measure current consumed by module
// https://www.youtube.com/watch?v=SiHfjzcqnU4
// [FIXME] Check properly
float GetCurrent(byte cur_pin) {
float volt_raw = (5.0 / 1023.0) * analogRead(cur_pin);
float volt = volt_raw * -gCUR_QOV + SEN0098_OFFSET; // Trimming value to make current equal to 0 when no current
return volt / gCUR_FACT; // Actual current
}
// Measure the tension provided by the PSU
float GetTension(byte vol_pin) {
float vol_raw = analogRead(vol_pin) * (5.0 / 1023.0);
return vol_raw * (DIV_RES1 + DIV_RES2) / (DIV_RES2);
}
/*******************************************************************************
Utils
Miscellaneous utilities.
--------------------------------------------------------------------------------
(c) Copyright 2022 University of Liege
Author: Thomas Lambert <t.lambert@uliege.be>
ULiege - Aeroelasticity and Experimental Aerodynamics
MIT License
Repo: https://gitlab.uliege.be/thlamb/mecharaptor-controller
*******************************************************************************/
// Converts frequence to ESC angle to use with Servo library
int FreqToEsc(float freq) {
// Need to scale times 100 so we can have better precision
int esc_val = freq * (180.0 / RpmToFreq(gMAX_RPM));
if (esc_val < gMIN_ESC_VAL) {
esc_val = gMIN_ESC_VAL;
} else if (esc_val > gMAX_ESC_VAL) {
esc_val = gMAX_ESC_VAL;
}
return esc_val;
}
// Converts RPM to Flapping frequency
float RpmToFreq(int rpm) {
return rpm * GEAR_RATIO / 60.0;
}
// Convert encoder position to degree
float PosToDeg(unsigned int pos) {
return pos * 360.0 / ENC_PRECISION;
}
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment