Skip to content

Commit

Permalink
Started inner loop control tuning
Browse files Browse the repository at this point in the history
  • Loading branch information
VSangtani authored and saturn691 committed May 23, 2024
1 parent ff7e72c commit a4b5f46
Show file tree
Hide file tree
Showing 9 changed files with 447 additions and 0 deletions.
5 changes: 5 additions & 0 deletions control/.gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,5 @@
.pio
.vscode/.browse.c_cpp.db*
.vscode/c_cpp_properties.json
.vscode/launch.json
.vscode/ipch
10 changes: 10 additions & 0 deletions control/.vscode/extensions.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,10 @@
{
// See http://go.microsoft.com/fwlink/?LinkId=827846
// for the documentation about the extensions.json format
"recommendations": [
"platformio.platformio-ide"
],
"unwantedRecommendations": [
"ms-vscode.cpptools-extension-pack"
]
}
3 changes: 3 additions & 0 deletions control/.vscode/settings.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,3 @@
{
"cmake.configureOnOpen": true
}
39 changes: 39 additions & 0 deletions control/include/README
Original file line number Diff line number Diff line change
@@ -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 changes: 46 additions & 0 deletions control/lib/README
Original file line number Diff line number Diff line change
@@ -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
18 changes: 18 additions & 0 deletions control/platformio.ini
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
; 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:esp32-c3-devkitc-02]
platform = espressif32
board = esp32dev
framework = arduino
lib_deps =
khoih-prog/TimerInterrupt_Generic@^1.13.0
adafruit/Adafruit MPU6050@^2.2.4
monitor_speed = 115200
159 changes: 159 additions & 0 deletions control/src/main.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,159 @@
#include <Arduino.h>
#include <TimerInterrupt_Generic.h>
#include <Adafruit_MPU6050.h>
#include <Adafruit_Sensor.h>
#include <step.h>
#include <chrono>

// The Stepper pins
#define STEPPER1_DIR_PIN 16 //Arduino D9
#define STEPPER1_STEP_PIN 17 //Arduino D8
#define STEPPER2_DIR_PIN 4 //Arduino D11
#define STEPPER2_STEP_PIN 14 //Arduino D10
#define STEPPER_EN 15 //Arduino D12

// Diagnostic pin for oscilloscope
#define TOGGLE_PIN 32 //Arduino A4

const int PRINT_INTERVAL = 50;
const double LOOP_INTERVAL = 5;
const int STEPPER_INTERVAL_US = 10;

//Global objects
ESP32Timer ITimer(3);
Adafruit_MPU6050 mpu; //Default pins for I2C are SCL: IO22/Arduino D3, SDA: IO21/Arduino D4

step step1(STEPPER_INTERVAL_US,STEPPER1_STEP_PIN,STEPPER1_DIR_PIN );
step step2(STEPPER_INTERVAL_US,STEPPER2_STEP_PIN,STEPPER2_DIR_PIN );


//Interrupt Service Routine for motor update
//Note: ESP32 doesn't support floating point calculations in an ISR
bool TimerHandler(void * timerNo)
{
static bool toggle = false;

//Update the stepper motors
step1.runStepper();
step2.runStepper();

//Indicate that the ISR is running
digitalWrite(TOGGLE_PIN,toggle);
toggle = !toggle;
return true;
}

void setup()
{
Serial.begin(115200);
pinMode(TOGGLE_PIN,OUTPUT);

// Try to initialize Accelerometer/Gyroscope
if (!mpu.begin()) {
Serial.println("Failed to find MPU6050 chip");
while (1) {
delay(10);
}
}
Serial.println("MPU6050 Found!");

mpu.setAccelerometerRange(MPU6050_RANGE_2_G);
mpu.setGyroRange(MPU6050_RANGE_250_DEG);
mpu.setFilterBandwidth(MPU6050_BAND_44_HZ);

//Attach motor update ISR to timer to run every STEPPER_INTERVAL_US μs
if (!ITimer.attachInterruptInterval(STEPPER_INTERVAL_US, TimerHandler)) {
Serial.println("Failed to start stepper interrupt");
while (1) delay(10);
}
Serial.println("Initialised Interrupt for Stepper");

//Set motor acceleration values
step1.setAccelerationRad(30.0);
step2.setAccelerationRad(30.0);

//Enable the stepper motor drivers
pinMode(STEPPER_EN,OUTPUT);
digitalWrite(STEPPER_EN, false);

}

void loop()
{
//Static variables are initialised once and then the value is remembered betweeen subsequent calls to this function
static unsigned long printTimer = 0; //time of the next print
static unsigned long loopTimer = 0; //time of the next control update
static double tiltx = 0.0;
static double gyrox = 0.0; //current tilt angle
static double gyroangle = 0.0;
static double theta_n = 0.0;


float kp = 2;
float ki = 0.002; //potentially don't need if we get the setpoint right (correct offset calibration)
float kd = 1;
float setpoint = -0.51;
double error, previous_error = 0, integral = 0, derivative = 0, previous_derivative = 0, Pout, Iout, Dout, motor_out;

//Run the control loop every LOOP_INTERVAL ms
if (millis() > loopTimer) {
loopTimer += LOOP_INTERVAL;

// Fetch data from MPU6050
sensors_event_t a, g, temp;
mpu.getEvent(&a, &g, &temp);

//Calculate Tilt using accelerometer and sin x = x approximation for a small tilt angle
tiltx = asin(a.acceleration.z/9.81)-0.05;

gyrox = g.gyro.y - 0.04;
gyroangle = gyroangle + (gyrox*(LOOP_INTERVAL));

theta_n = 0.04*(tiltx*100) + 0.96*((gyrox*LOOP_INTERVAL)/10 + theta_n);

//PIDeez Nuts


error = setpoint - theta_n;

Pout = kp*error;

integral = integral + error*(LOOP_INTERVAL/1000);
Iout = ki*integral;

derivative = ((error - previous_error)/LOOP_INTERVAL)*1000;
derivative = previous_derivative + 0.2*(derivative-previous_derivative);
previous_derivative = derivative;

Dout = kd*derivative;

motor_out = Pout + Iout + Dout;

previous_error = error;

//Set target motor speed

step1.setTargetSpeedRad(motor_out);
step2.setTargetSpeedRad(-motor_out);
}

//Print updates every PRINT_INTERVAL ms
// if (millis() > printTimer) {
// printTimer += PRINT_INTERVAL;

// Serial.print(error);
// Serial.print(' ');
// Serial.print(motor_out);
// Serial.println();

// // Serial.print(tiltx*100);
// // Serial.print(' ');
// // Serial.print(step1.getSpeedRad());
// // Serial.print(' ');
// // Serial.print(gyroangle/10);
// // Serial.print(' ');
// // Serial.print(theta_n);
// // Serial.println();
// }

}
Loading

0 comments on commit a4b5f46

Please sign in to comment.