Compare commits

...

4 Commits

Author SHA1 Message Date
Stedd 42034ab9e8 this is not working 2023-10-19 20:43:01 +02:00
Stedd 72716f2abd quicksave 2023-10-19 00:26:26 +02:00
Stedd b5a53fa8c9 Cleanup 2023-10-18 22:16:53 +02:00
Stedd 23c84d2e41 Added PS3 controller 2023-10-18 21:48:18 +02:00
7 changed files with 257 additions and 269 deletions

View File

@ -7,7 +7,7 @@ const int gyro_overflow_value = 4558; // 4096+512-50=4558 ?
//IMU VARIABLES
int ax, ay, az;
int cx, cy, cz;
int gx, gy, gz;
float gx, gy, gz;
float gt;
float acc_pitch;
float pitch_rate;
@ -16,26 +16,30 @@ float pitch_prev = 0;
void readIMU() {
// Serial.println("ReadingIMU");
//Acceletometer
ax = convertInt(IMU.accelerometer_x( IMU.readFromAccelerometer() ), acc_overflow_value);
ay = convertInt(IMU.accelerometer_y( IMU.readFromAccelerometer() ), acc_overflow_value);
az = convertInt(IMU.accelerometer_z( IMU.readFromAccelerometer() ), acc_overflow_value);
int* accelerometerReadings = IMU.readFromAccelerometer();
ax = convertInt(IMU.accelerometer_x(accelerometerReadings), acc_overflow_value);
ay = convertInt(IMU.accelerometer_y(accelerometerReadings), acc_overflow_value);
az = convertInt(IMU.accelerometer_z(accelerometerReadings), acc_overflow_value);
//Magnetometer
cx = IMU.compass_x( IMU.readFromCompass() );
cy = IMU.compass_y( IMU.readFromCompass() );
cz = IMU.compass_z( IMU.readFromCompass() );
int* compassReadings = IMU.readFromCompass();
cx = IMU.compass_x(compassReadings);
cy = IMU.compass_y(compassReadings);
cz = IMU.compass_z(compassReadings);
// Gyrocope
gx = convertInt(IMU.gyro_x( IMU.readGyro() ), gyro_overflow_value); // gx - Pitch rate
gy = convertInt(IMU.gyro_y( IMU.readGyro() ), gyro_overflow_value); // gy - Roll rate
gz = convertInt(IMU.gyro_z( IMU.readGyro() ), gyro_overflow_value); // gz - Yaw rate
// // Gyrocope
// float* gyroReadings = IMU.readGyro();
// gx = convertInt(IMU.gyro_x(gyroReadings), gyro_overflow_value); // gx - Pitch rate
// gy = convertInt(IMU.gyro_y(gyroReadings), gyro_overflow_value); // gy - Roll rate
// gz = convertInt(IMU.gyro_z(gyroReadings), gyro_overflow_value); // gz - Yaw rate
//Temperature sensor
gt = IMU.temp ( IMU.readGyro() );
// //Temperature sensor
// gt = IMU.temp(gyroReadings);
// Pitch angle from accelerometer
@ -49,8 +53,6 @@ void readIMU() {
//Complementary filter
pitch = acc_pitch * (1 - alpha) + (((pitch_rate * dT_s) + pitch_prev) * alpha);
pitch_prev = pitch;
}

View File

@ -2,7 +2,8 @@
#include <GY_85.h>
#include <Wire.h>
#include <MatrixMath.h>
#include <Math.h>
#include <Ps3Controller.h>
//Declare library objects
GY_85 IMU;
@ -17,8 +18,8 @@ const byte M1_A = 16;
const byte M1_B = 17;
const byte M2_A = 18;
const byte M2_B = 19;
const byte IMU_I2C_SCL = 26;
const byte IMU_I2C_SDA = 27;
const int IMU_I2C_SCL = 26;
const int IMU_I2C_SDA = 27;
//Time variables
@ -39,6 +40,8 @@ long int m2Raw, m2RawLast;
volatile bool M1_A_state, M1_B_state;
volatile bool M2_A_state, M2_B_state;
//PS3 Controller variables
const char* _ps3Address = "18:5e:0f:92:00:6c";
void setup() {
//Initialize serial
@ -46,17 +49,18 @@ void setup() {
delay(10);
//Initialice I2C
Wire.begin(IMU_I2C_SCL, IMU_I2C_SDA);
delay(10);
Wire.setPins(IMU_I2C_SCL, IMU_I2C_SDA);
//delay(10);
//Initialize IMU
Serial.println("Before IMU init");
IMU.init();
//Might need some logic here to mke sure the gyro is calibrated correctly, or hardcode the values...
IMU.GyroCalibrate();
//IMU.init();
Serial.println("After IMU init");
delay(10);
//Initialize encoder interrupts
initInterrupt();
initEncoderInterrupt();
//Initialize encoders
m1Raw = 0;
@ -78,12 +82,12 @@ void setup() {
//Initialize differential drive inverse kinematics
initMotors();
// Initialize Remote control
initRemote();
//Initialize PS3 controller connection
Ps3.begin(_ps3Address);
}
void loop() {
// Serial.println("Loop");
//Update time variables
tNow = micros();
dT = tNow - tLast; //[Cycle time in microseconds]
@ -108,4 +112,6 @@ void loop() {
//Delay
delay(5);
//Test
}

View File

@ -7,8 +7,7 @@ void IRAM_ATTR m1_A_changed() {
if (M1_A_state == HIGH) {
if (M1_B_state == HIGH) {
m1Raw = m1Raw - 1;
}
else if (M1_B_state == LOW) {
} else if (M1_B_state == LOW) {
m1Raw = m1Raw + 1;
}
}
@ -17,8 +16,7 @@ void IRAM_ATTR m1_A_changed() {
else if (M1_A_state == LOW) {
if (M1_B_state == HIGH) {
m1Raw = m1Raw + 1;
}
else if (M1_B_state == LOW) {
} else if (M1_B_state == LOW) {
m1Raw = m1Raw - 1;
}
}
@ -33,8 +31,7 @@ void IRAM_ATTR m1_B_changed() {
if (M1_B_state == HIGH) {
if (M1_A_state == HIGH) {
m1Raw = m1Raw + 1;
}
else if (M1_A_state == LOW) {
} else if (M1_A_state == LOW) {
m1Raw = m1Raw - 1;
}
}
@ -43,8 +40,7 @@ void IRAM_ATTR m1_B_changed() {
else if (M1_B_state == LOW) {
if (M1_A_state == HIGH) {
m1Raw = m1Raw - 1;
}
else if (M1_A_state == LOW) {
} else if (M1_A_state == LOW) {
m1Raw = m1Raw + 1;
}
}
@ -58,8 +54,7 @@ void IRAM_ATTR m2_A_changed() {
if (M2_A_state == HIGH) {
if (M2_B_state == HIGH) {
m2Raw = m2Raw + 1;
}
else if (M2_B_state == LOW) {
} else if (M2_B_state == LOW) {
m2Raw = m2Raw - 1;
}
}
@ -68,8 +63,7 @@ void IRAM_ATTR m2_A_changed() {
else if (M2_A_state == LOW) {
if (M2_B_state == HIGH) {
m2Raw = m2Raw - 1;
}
else if (M2_B_state == LOW) {
} else if (M2_B_state == LOW) {
m2Raw = m2Raw + 1;
}
}
@ -84,8 +78,7 @@ void IRAM_ATTR m2_B_changed() {
if (M2_B_state == HIGH) {
if (M2_A_state == HIGH) {
m2Raw = m2Raw - 1;
}
else if (M2_A_state == LOW) {
} else if (M2_A_state == LOW) {
m2Raw = m2Raw + 1;
}
}
@ -94,21 +87,23 @@ void IRAM_ATTR m2_B_changed() {
else if (M2_B_state == LOW) {
if (M2_A_state == HIGH) {
m2Raw = m2Raw + 1;
}
else if (M2_A_state == LOW) {
} else if (M2_A_state == LOW) {
m2Raw = m2Raw - 1;
}
}
}
void initInterrupt(){
void initEncoderInterrupt() {
pinMode(M1_ENC_A, INPUT_PULLUP);
pinMode(M1_ENC_B, INPUT_PULLUP);
pinMode(M2_ENC_A, INPUT_PULLUP);
pinMode(M2_ENC_B, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(M1_ENC_A), m1_A_changed, CHANGE);
pinMode(M1_ENC_B, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(M1_ENC_B), m1_B_changed, CHANGE);
pinMode(M2_ENC_A, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(M2_ENC_A), m2_A_changed, CHANGE);
pinMode(M2_ENC_B, INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(M2_ENC_B), m2_B_changed, CHANGE);
}

View File

@ -1,36 +0,0 @@
//Variables
const byte NO_CHANNELS = 2;
const byte CHANNEL_PINS[] = {12, 14};
volatile unsigned int interruptTime_ch1, interruptTimeLast_ch1;
volatile unsigned int interruptTime_ch2, interruptTimeLast_ch2;
volatile unsigned int pwm_time_ch1, pwm_time_ch2;
void ch1_interrupt() {
interruptTime_ch1 = micros();
if (interruptTime_ch1 >interruptTimeLast_ch1 && (interruptTime_ch1 - interruptTimeLast_ch1)< 2100){
pwm_time_ch1 = interruptTime_ch1 - interruptTimeLast_ch1;
}
interruptTimeLast_ch1 = interruptTime_ch1;
}
void ch2_interrupt() {
interruptTime_ch2 = micros();
if (interruptTime_ch2 > interruptTimeLast_ch2 && (interruptTime_ch2 - interruptTimeLast_ch2)< 2100 ){
pwm_time_ch2 = interruptTime_ch2 - interruptTimeLast_ch2;
}
interruptTimeLast_ch2 = interruptTime_ch2;
}
void initRemote(){
//Ch1
pinMode(CHANNEL_PINS[0], INPUT_PULLUP);
attachInterrupt(digitalPinToInterrupt(CHANNEL_PINS[0]), ch1_interrupt, CHANGE);
//Ch2
pinMode(CHANNEL_PINS[1], INPUT);
attachInterrupt(digitalPinToInterrupt(CHANNEL_PINS[1]), ch2_interrupt, CHANGE);
}

View File

@ -28,7 +28,7 @@ float SC_cont_out;
float TC_cont_out;
float OL_cont_out;
float ref_IL, act_IL, error_IL, IL_cont_out, iError_IL, IL_anti_windup;
float speedCmd1, speedCmd2;
//Matrices
@ -56,17 +56,9 @@ void motors() {
//Calculate robot linear and angular velocity
Matrix.Multiply((mtx_type*)inv_Kin, (mtx_type*)motor_ang_vel, 2, 2, 1, (mtx_type*)vel_Matrix);
// Remote control commands
if (pwm_time_ch1 == 0 && pwm_time_ch2 == 0){
rem_turn_speed_ref = 0;
rem_speed_ref = 0;
}
else{
rem_turn_speed_ref = floatMap(pwm_time_ch1, 992.0, 2015.0, -3.75, 3.75);
rem_speed_ref = floatMap(pwm_time_ch2, 982.0, 2005.0, -0.35, 0.35);
}
//Get Control Commands
rem_turn_speed_ref = floatMap(Ps3.data.analog.stick.ly, -128.0, 127.0, -3.75, 3.75);
rem_speed_ref = floatMap(Ps3.data.analog.stick.ry, -128.0, 127.0, -0.35, 0.35);
// Speed Controller
SC_cont_out = PController(rem_speed_ref, vel_Matrix[0][0], K_SC);
@ -92,20 +84,22 @@ void motors() {
M2_Speed_CMD = IL_cont_out + TC_cont_out;
//Sum speed command for motors
// M1_Speed_CMD = 0;
// M2_Speed_CMD = 0;
speedCmd1 = floatMap(Ps3.data.analog.stick.ry, -128.0, 127.0, -1.0, 1.0);
M1_Speed_CMD = MOTOR_SATURATION * speedCmd1;
motorControl(1, M1_Speed_CMD, MOTOR_SATURATION, DEADBAND_M1_POS, DEADBAND_M1_NEG);
speedCmd2 = floatMap(Ps3.data.analog.stick.ly, -128.0, 127.0, -1.0, 1.0);
M2_Speed_CMD = MOTOR_SATURATION * speedCmd2;
motorControl(2, M2_Speed_CMD, MOTOR_SATURATION, DEADBAND_M2_POS, DEADBAND_M2_NEG);
//Motor control
IL_anti_windup = motorControl(1, M1_Speed_CMD, MOTOR_SATURATION, DEADBAND_M1_POS, DEADBAND_M1_NEG);
IL_anti_windup = IL_anti_windup + motorControl(2, M2_Speed_CMD, MOTOR_SATURATION, DEADBAND_M2_POS, DEADBAND_M2_NEG);
IL_anti_windup = IL_anti_windup/2;
// IL_anti_windup = motorControl(1, M1_Speed_CMD, MOTOR_SATURATION, DEADBAND_M1_POS, DEADBAND_M1_NEG);
// IL_anti_windup = IL_anti_windup + motorControl(2, M2_Speed_CMD, MOTOR_SATURATION, DEADBAND_M2_POS, DEADBAND_M2_NEG);
// IL_anti_windup = IL_anti_windup / 2;
//Update variables for next scan cycle
m1RawLast = m1Raw;
m2RawLast = m2Raw;
}
float PController(float ref_, float act_, float k_) {
@ -140,8 +134,7 @@ float motorControl(byte motorID, int speedCMD_, int saturation, float dbPos_, fl
//Deadband
if (speedCMD_ > 0 && speedCMD_ < dbPos_) {
speedCMD_ = dbPos_;
}
else if (speedCMD_ < 0 && speedCMD_ > -dbNeg_) {
} else if (speedCMD_ < 0 && speedCMD_ > -dbNeg_) {
speedCMD_ = -dbNeg_;
}
@ -149,8 +142,7 @@ float motorControl(byte motorID, int speedCMD_, int saturation, float dbPos_, fl
else if (speedCMD_ > saturation) {
windup = saturation - speedCMD_;
speedCMD_ = saturation;
}
else if (speedCMD_ < -saturation) {
} else if (speedCMD_ < -saturation) {
windup = saturation - speedCMD_;
speedCMD_ = -saturation;
}
@ -163,16 +155,13 @@ float motorControl(byte motorID, int speedCMD_, int saturation, float dbPos_, fl
if (speedCMD_ > 0) {
ledcWrite(ch1, 0);
ledcWrite(ch2, speedCMD_);
}
else if (speedCMD_ < 0) {
} else if (speedCMD_ < 0) {
ledcWrite(ch1, -1 * speedCMD_);
ledcWrite(ch2, 0);
}
else if (speedCMD_ == 0) {
} else if (speedCMD_ == 0) {
ledcWrite(ch1, 0);
ledcWrite(ch2, 0);
}
return windup;
}

View File

@ -8,8 +8,8 @@ void plot(){
// Serial.print(" ");
// IMU
// Serial.print ( "Pitch:" );
// Serial.print ( pitch );
Serial.print ( "Pitch:" );
Serial.println ( pitch );
// Serial.print (" ");
// Serial.print ( "Accelerometer_Pitch:" );
// Serial.print ( acc_pitch );
@ -52,12 +52,15 @@ void plot(){
// Serial.print("BalanceILControllerOut:");
// Serial.print(IL_cont_out);
// Serial.print(" ");
// Serial.print("TurnControllerOut:");
// Serial.println(TC_cont_out);
// Serial.print("SpeedCmd1:");
// Serial.println(speedCmd1);
// Serial.print(" ");
// Serial.print("M1_CMD:");
// Serial.print(M1_Speed_CMD);
// Serial.print(" ");
// Serial.print("SpeedCmd2:");
// Serial.println(speedCmd2);
// Serial.print(" ");
// Serial.print("M2_CMD:");
// Serial.println(M2_Speed_CMD);
@ -72,4 +75,19 @@ void plot(){
// Serial.print(" ");
// Serial.print("botAngVel:");
// Serial.println(vel_Matrix[1][0]);
// //PS3 Controller
// if (Ps3.isConnected()) {
// Serial.print("lx:");
// Serial.print(Ps3.data.analog.stick.lx);
// Serial.print(",");
// Serial.print("ly:");
// Serial.print(Ps3.data.analog.stick.ly);
// Serial.print(",");
// Serial.print("rx:");
// Serial.print(Ps3.data.analog.stick.rx);
// Serial.print(",");
// Serial.print("ry:");
// Serial.println(Ps3.data.analog.stick.ry);
// }
}

View File

@ -1 +1,15 @@
# Balancebot
# BalanceBot
## Arduino Board Settings
My board has this etched on it: ESP-WROOM-32
These settings allow upload:
* Board: FireBeetle-ESP32
## Dependencies
[Ps3Controller.h](https://github.com/jvpernis/esp32-ps3)
[MatrixMath.h](https://github.com/eecharlie/MatrixMath)
[GY_85.h](https://github.com/sqrtmo/GY-85-arduino/tree/master)