Linear speed
This commit is contained in:
parent
c4d0df4730
commit
25b15b5ca0
12
Main/IMU.ino
12
Main/IMU.ino
|
@ -1,3 +1,11 @@
|
||||||
|
//IMU variables
|
||||||
|
|
||||||
|
int ax_, ay_, az_;
|
||||||
|
int ax, ay, az;
|
||||||
|
int cx, cy, cz;
|
||||||
|
float gx, gy, gz, gt;
|
||||||
|
float acc_pitch;
|
||||||
|
|
||||||
void readIMU() {
|
void readIMU() {
|
||||||
ax_ = GY85.accelerometer_x( GY85.readFromAccelerometer() );
|
ax_ = GY85.accelerometer_x( GY85.readFromAccelerometer() );
|
||||||
ay_ = GY85.accelerometer_y( GY85.readFromAccelerometer() );
|
ay_ = GY85.accelerometer_y( GY85.readFromAccelerometer() );
|
||||||
|
@ -43,12 +51,12 @@ void readIMU() {
|
||||||
// map(ay,-140,140,-1,1)
|
// map(ay,-140,140,-1,1)
|
||||||
// map(az,-140,140,-1,1)
|
// map(az,-140,140,-1,1)
|
||||||
|
|
||||||
// Serial.print ( " x:" );
|
// Serial.print ( " x:" );
|
||||||
// Serial.print ( ax );
|
// Serial.print ( ax );
|
||||||
// Serial.print ( "," );
|
// Serial.print ( "," );
|
||||||
// Serial.print ( ay );
|
// Serial.print ( ay );
|
||||||
// Serial.print ( "," );
|
// Serial.print ( "," );
|
||||||
// Serial.print ( az );
|
// Serial.println ( az );
|
||||||
// Serial.print ( "," );
|
// Serial.print ( "," );
|
||||||
// Serial.println ( acc_pitch);
|
// Serial.println ( acc_pitch);
|
||||||
|
|
||||||
|
|
|
@ -2,21 +2,10 @@
|
||||||
#include "GY_85.h"
|
#include "GY_85.h"
|
||||||
#include <Wire.h>
|
#include <Wire.h>
|
||||||
|
|
||||||
//System variables
|
|
||||||
unsigned long now = micros();
|
|
||||||
|
|
||||||
|
|
||||||
//IMU variables
|
|
||||||
GY_85 GY85; //create the object
|
GY_85 GY85; //create the object
|
||||||
int ax_, ay_, az_;
|
|
||||||
int ax, ay, az;
|
|
||||||
int cx, cy, cz;
|
|
||||||
float gx, gy, gz, gt;
|
|
||||||
float acc_pitch;
|
|
||||||
signed int speed_setp;
|
|
||||||
|
|
||||||
//Random
|
//System variables
|
||||||
int i, modifier;
|
unsigned long tNow = micros();
|
||||||
|
|
||||||
//Motor Control variables
|
//Motor Control variables
|
||||||
const byte m1_in1 = 18;
|
const byte m1_in1 = 18;
|
||||||
|
@ -25,7 +14,7 @@ const byte m1_in2 = 19;
|
||||||
//int m2_in2 = 17;
|
//int m2_in2 = 17;
|
||||||
|
|
||||||
//Encoders variables
|
//Encoders variables
|
||||||
long int m1Raw, m1RawLast;
|
long int m1Raw,m1RawLast;
|
||||||
const byte pin_m1_A = 34;
|
const byte pin_m1_A = 34;
|
||||||
const byte pin_m1_B = 35;
|
const byte pin_m1_B = 35;
|
||||||
volatile bool A_state;
|
volatile bool A_state;
|
||||||
|
@ -124,20 +113,19 @@ void setup() {
|
||||||
// ledcSetup(3, 12000, 8);
|
// ledcSetup(3, 12000, 8);
|
||||||
// ledcSetup(4, 12000, 8);
|
// ledcSetup(4, 12000, 8);
|
||||||
|
|
||||||
//Random
|
Serial.println("Reference,Actual,SpeedCommand");
|
||||||
i = 0;
|
|
||||||
modifier = 2;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void loop() {
|
void loop() {
|
||||||
//Update system variables
|
//Update system variables
|
||||||
now = micros();
|
tNow = micros();
|
||||||
|
|
||||||
//Only print encoder value if value changed since last print
|
//// //Only print encoder value if value changed since last print
|
||||||
if (m1Raw != m1RawLast) {
|
// if (m1Raw != m1RawLast) {
|
||||||
Serial.println(m1Raw);
|
// Serial.println(m1Raw);
|
||||||
m1RawLast = m1Raw;
|
// m1RawLast = m1Raw;
|
||||||
}
|
// }
|
||||||
|
|
||||||
//Sense
|
//Sense
|
||||||
readIMU();
|
readIMU();
|
||||||
|
|
|
@ -1,13 +1,47 @@
|
||||||
|
//Constants
|
||||||
|
const float wheel_diameter = 0.067708;
|
||||||
|
const float pulses_per_turn = 1320.0;
|
||||||
|
//Tuning
|
||||||
|
const float K = 2;
|
||||||
|
const float I = 10;
|
||||||
|
|
||||||
|
//Help variables
|
||||||
|
int dEnc, dT;
|
||||||
|
float dTurn, ang_vel, lin_vel, ang_vel_filtered, lin_vel_filtered;
|
||||||
|
unsigned long tLast;
|
||||||
|
|
||||||
|
float speed_setp,referenceSpeed,actualSpeed;
|
||||||
|
float error, iError;
|
||||||
|
int speedCMD;
|
||||||
|
|
||||||
|
|
||||||
void motorControl() {
|
void motorControl() {
|
||||||
//Motor 1
|
//Motor 1
|
||||||
speed_setp = round (map(acc_pitch, -90.0, 90.0, -4096, 4096));
|
speed_setp = map(acc_pitch, -90.0, 90.0, -4096, 4096);
|
||||||
if (speed_setp > 0) {
|
referenceSpeed = speed_setp;
|
||||||
ledcWrite(1, speed_setp);
|
actualSpeed = lin_vel*4096;
|
||||||
ledcWrite(2, 0);
|
error = referenceSpeed - actualSpeed;
|
||||||
|
iError = iError + (error*dT*pow(10,-6)*I);
|
||||||
|
speedCMD = round((error*K)+iError);
|
||||||
|
|
||||||
|
// Saturation
|
||||||
|
if(speedCMD>4096){
|
||||||
|
speedCMD = 4096;
|
||||||
}
|
}
|
||||||
else if (speed_setp < 0) {
|
else if(speedCMD < -4096){
|
||||||
|
speedCMD = -4096;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
speedCMD = speedCMD;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (speedCMD > 0) {
|
||||||
ledcWrite(1, 0);
|
ledcWrite(1, 0);
|
||||||
ledcWrite(2, -1 * speed_setp);
|
ledcWrite(2, speedCMD);
|
||||||
|
}
|
||||||
|
else if (speedCMD < 0) {
|
||||||
|
ledcWrite(1, -1 * speedCMD);
|
||||||
|
ledcWrite(2, 0);
|
||||||
}
|
}
|
||||||
// Serial.print (acc_pitch);
|
// Serial.print (acc_pitch);
|
||||||
// Serial.print ( "," );
|
// Serial.print ( "," );
|
||||||
|
@ -21,4 +55,28 @@ void motorControl() {
|
||||||
//Motor 2
|
//Motor 2
|
||||||
// ledcWrite(3, 255);
|
// ledcWrite(3, 255);
|
||||||
// ledcWrite(4, 255);
|
// ledcWrite(4, 255);
|
||||||
|
|
||||||
|
//Calculate speed from encoders
|
||||||
|
dEnc = m1Raw - m1RawLast; //[pulses]
|
||||||
|
dT = tNow - tLast; //[micro sec]
|
||||||
|
dTurn = dEnc / pulses_per_turn;
|
||||||
|
|
||||||
|
ang_vel = (dTurn * 2 * PI) /(dT*0.000001);
|
||||||
|
lin_vel = (dTurn * wheel_diameter * PI) /(dT*0.000001);
|
||||||
|
|
||||||
|
Serial.print(referenceSpeed);
|
||||||
|
Serial.print ( "," );
|
||||||
|
Serial.println(actualSpeed);
|
||||||
|
// Serial.print ( "," );
|
||||||
|
// Serial.println(speedCMD);
|
||||||
|
// Serial.print ( "," );
|
||||||
|
// Serial.println(lin_vel);
|
||||||
|
// Serial.print ( "," );
|
||||||
|
|
||||||
|
//update variables for next scan cycle
|
||||||
|
m1RawLast = m1Raw;
|
||||||
|
tLast = tNow;
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue