mirror of
https://gitlab.com/yikestone/qt_pi.git
synced 2025-08-03 21:54:12 +05:30
Added IMU support
This commit is contained in:
parent
faf11669a5
commit
57dca60d0c
@ -18,13 +18,13 @@ encoder_resolution: 240 # from Pololu for 131:1 motors
|
|||||||
motors_reversed: False
|
motors_reversed: False
|
||||||
gear_reduction: 1.0
|
gear_reduction: 1.0
|
||||||
# === PID parameters
|
# === PID parameters
|
||||||
lKp: 50
|
lKp: 45
|
||||||
lKd: 10
|
lKd: 0
|
||||||
lKi: 0
|
lKi: 5
|
||||||
lKo: 20
|
lKo: 3
|
||||||
rKp: 50
|
rKp: 45
|
||||||
rKd: 10
|
rKd: 0
|
||||||
rKi: 0
|
rKi: 5
|
||||||
rKo: 20
|
rKo: 3
|
||||||
|
|
||||||
#accel_limit: 0.1
|
#accel_limit: 0.1
|
||||||
|
@ -10,6 +10,19 @@
|
|||||||
#include "motor_driver.h"
|
#include "motor_driver.h"
|
||||||
#include "encoder_driver.h"
|
#include "encoder_driver.h"
|
||||||
#include "diff_controller.h"
|
#include "diff_controller.h"
|
||||||
|
#include <Wire.h>
|
||||||
|
#include "I2Cdev.h"
|
||||||
|
#include "MPU9150.h"
|
||||||
|
#include "Kalman.h"
|
||||||
|
|
||||||
|
Kalman filter;
|
||||||
|
MPU9150 accelGyroMag;
|
||||||
|
float batt_lvl;
|
||||||
|
int16_t gx;
|
||||||
|
float mx, my, mz;
|
||||||
|
int dt;
|
||||||
|
|
||||||
|
|
||||||
#define PID_RATE 30 // Hz
|
#define PID_RATE 30 // Hz
|
||||||
const int PID_INTERVAL = 1000 / PID_RATE;
|
const int PID_INTERVAL = 1000 / PID_RATE;
|
||||||
unsigned long nextPID = PID_INTERVAL;
|
unsigned long nextPID = PID_INTERVAL;
|
||||||
@ -23,7 +36,7 @@ char argv1[16];
|
|||||||
char argv2[16];
|
char argv2[16];
|
||||||
long arg1;
|
long arg1;
|
||||||
long arg2;
|
long arg2;
|
||||||
|
float heading = 0.0;
|
||||||
void resetCommand() {
|
void resetCommand() {
|
||||||
cmd = NULL;
|
cmd = NULL;
|
||||||
memset(argv1, 0, sizeof(argv1));
|
memset(argv1, 0, sizeof(argv1));
|
||||||
@ -109,8 +122,11 @@ int runCommand() {
|
|||||||
Serial.println("OK");
|
Serial.println("OK");
|
||||||
break;
|
break;
|
||||||
case BATTERY_LVL:
|
case BATTERY_LVL:
|
||||||
Serial.println(analogRead(A0));
|
Serial.println(batt_lvl);
|
||||||
break;
|
break;
|
||||||
|
case IMU:
|
||||||
|
Serial.println(heading);
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
Serial.println("Invalid Command");
|
Serial.println("Invalid Command");
|
||||||
break;
|
break;
|
||||||
@ -119,9 +135,21 @@ int runCommand() {
|
|||||||
|
|
||||||
/* Setup function--runs once at startup. */
|
/* Setup function--runs once at startup. */
|
||||||
void setup() {
|
void setup() {
|
||||||
|
Wire.setClock(400000);
|
||||||
|
Wire.begin();
|
||||||
Serial.begin(BAUDRATE);
|
Serial.begin(BAUDRATE);
|
||||||
|
accelGyroMag.initialize();
|
||||||
|
delay(100);
|
||||||
|
accelGyroMag.getHadjusted(&my, &mx, &mz);
|
||||||
|
heading = atan2(-mz, my) * RAD_TO_DEG;
|
||||||
|
filter.setQangle(0.0001);
|
||||||
|
filter.setQbias(0.003);
|
||||||
|
filter.setRmeasure(0.05);
|
||||||
|
filter.setAngle(heading);
|
||||||
|
|
||||||
pinMode(A0,INPUT);
|
pinMode(A0,INPUT);
|
||||||
digitalWrite(A0,1);
|
digitalWrite(A0,1);
|
||||||
|
batt_lvl = analogRead(A0);
|
||||||
DDRC &= ~(1<<LEFT_ENC_PIN_A);
|
DDRC &= ~(1<<LEFT_ENC_PIN_A);
|
||||||
DDRC &= ~(1<<LEFT_ENC_PIN_B);
|
DDRC &= ~(1<<LEFT_ENC_PIN_B);
|
||||||
DDRD &= ~(1<<RIGHT_ENC_PIN_A);
|
DDRD &= ~(1<<RIGHT_ENC_PIN_A);
|
||||||
@ -146,9 +174,30 @@ void setup() {
|
|||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
uint32_t timer;
|
||||||
void loop() {
|
void loop() {
|
||||||
|
|
||||||
|
gx = accelGyroMag.getRotationX();
|
||||||
|
accelGyroMag.getHadjusted(&my, &mx, &mz);
|
||||||
|
batt_lvl = ( analogRead(A0) * 12.22 / 800.0 ) * 0.001 + batt_lvl * 0.999;
|
||||||
|
|
||||||
|
double dt = (micros() - timer) / 1000000.0;
|
||||||
|
timer = micros();
|
||||||
|
|
||||||
|
|
||||||
|
float tempY = atan2(-mz, my) * RAD_TO_DEG;
|
||||||
|
|
||||||
|
if ((tempY < -90 && heading > 90) || (tempY > 90 && heading < -90)) {
|
||||||
|
filter.setAngle(tempY);
|
||||||
|
heading = tempY;
|
||||||
|
}
|
||||||
|
|
||||||
|
else
|
||||||
|
|
||||||
|
heading = filter.getAngle(tempY, gx / 131.0, dt);
|
||||||
|
|
||||||
|
//Serial.println(heading);
|
||||||
|
|
||||||
|
|
||||||
while (Serial.available() > 0) {
|
while (Serial.available() > 0) {
|
||||||
|
|
||||||
@ -199,6 +248,7 @@ void loop() {
|
|||||||
if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {;
|
if ((millis() - lastMotorCommand) > AUTO_STOP_INTERVAL) {;
|
||||||
setMotorSpeeds(0, 0);
|
setMotorSpeeds(0, 0);
|
||||||
moving = 0;
|
moving = 0;
|
||||||
|
resetPID();
|
||||||
}
|
}
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -1,16 +1,16 @@
|
|||||||
#ifndef COMMANDS_H
|
#ifndef COMMANDS_H
|
||||||
#define COMMANDS_H
|
#define COMMANDS_H
|
||||||
|
|
||||||
#define GET_BAUDRATE 'b'
|
|
||||||
#define READ_ENCODERS 'e'
|
|
||||||
#define MOTOR_SPEEDS 'm'
|
|
||||||
#define RESET_ENCODERS 'r'
|
|
||||||
#define UPDATE_PID_L 'L'
|
|
||||||
#define UPDATE_PID_R 'R'
|
|
||||||
#define DISP_PID_P 'z'
|
|
||||||
#define BATTERY_LVL 'B'
|
|
||||||
#define LEFT 0
|
|
||||||
#define RIGHT 1
|
|
||||||
|
|
||||||
|
#define GET_BAUDRATE 'b'
|
||||||
|
#define READ_ENCODERS 'e'
|
||||||
|
#define MOTOR_SPEEDS 'm'
|
||||||
|
#define RESET_ENCODERS 'r'
|
||||||
|
#define UPDATE_PID_L 'L'
|
||||||
|
#define UPDATE_PID_R 'R'
|
||||||
|
#define DISP_PID_P 'z'
|
||||||
|
#define BATTERY_LVL 'B'
|
||||||
|
#define LEFT 0
|
||||||
|
#define RIGHT 1
|
||||||
|
#define IMU 'i'
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -1,4 +1,3 @@
|
|||||||
|
|
||||||
typedef struct {
|
typedef struct {
|
||||||
double TargetTicksPerFrame;
|
double TargetTicksPerFrame;
|
||||||
long Encoder;
|
long Encoder;
|
||||||
@ -7,14 +6,14 @@ typedef struct {
|
|||||||
int PrevInput;
|
int PrevInput;
|
||||||
|
|
||||||
int ITerm;
|
int ITerm;
|
||||||
int Kp = 500;
|
int Kp = 45;
|
||||||
int Kd = 100;
|
int Kd = 0;
|
||||||
int Ki = 0;
|
int Ki = 5;
|
||||||
int Ko = 50;
|
int Ko = 3;
|
||||||
|
int base_pwm = 70;
|
||||||
long output;
|
long output;
|
||||||
|
|
||||||
}
|
}
|
||||||
|
|
||||||
SetPointInfo;
|
SetPointInfo;
|
||||||
|
|
||||||
SetPointInfo leftPID, rightPID;
|
SetPointInfo leftPID, rightPID;
|
||||||
@ -45,11 +44,11 @@ void doPID(SetPointInfo * p) {
|
|||||||
|
|
||||||
input = p->Encoder - p->PrevEnc;
|
input = p->Encoder - p->PrevEnc;
|
||||||
Perror = p->TargetTicksPerFrame - input;
|
Perror = p->TargetTicksPerFrame - input;
|
||||||
|
p->ITerm += (p->Ki) * Perror;
|
||||||
output = ((p->Kp) * Perror + (p->Kd) * (input - p->PrevInput) + p->ITerm) / (p->Ko);
|
output = p->base_pwm + ((p->Kp) * Perror + (p->Kd) * (input - p->PrevInput) + p->ITerm) / (p->Ko);
|
||||||
p->PrevEnc = p->Encoder;
|
p->PrevEnc = p->Encoder;
|
||||||
|
|
||||||
output += p->output;
|
//output += p->output;
|
||||||
|
|
||||||
if (output >= MAX_PWM)
|
if (output >= MAX_PWM)
|
||||||
output = MAX_PWM;
|
output = MAX_PWM;
|
||||||
@ -57,8 +56,6 @@ void doPID(SetPointInfo * p) {
|
|||||||
output = -MAX_PWM;
|
output = -MAX_PWM;
|
||||||
else
|
else
|
||||||
|
|
||||||
p->ITerm += (p->Ki) * Perror;
|
|
||||||
|
|
||||||
p->output = output;
|
p->output = output;
|
||||||
p->PrevInput = input;
|
p->PrevInput = input;
|
||||||
}
|
}
|
||||||
@ -73,9 +70,8 @@ void updatePID() {
|
|||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
if(leftPID.TargetTicksPerFrame != 0) doPID(&leftPID);
|
||||||
|
if(rightPID.TargetTicksPerFrame != 0) doPID(&rightPID);
|
||||||
|
|
||||||
doPID(&leftPID);
|
|
||||||
doPID(&rightPID);
|
|
||||||
setMotorSpeeds(leftPID.output, rightPID.output);
|
setMotorSpeeds(leftPID.output, rightPID.output);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -1,5 +1,5 @@
|
|||||||
#define LEFT_ENC_PIN_A PC4
|
#define LEFT_ENC_PIN_A PC2
|
||||||
#define LEFT_ENC_PIN_B PC5
|
#define LEFT_ENC_PIN_B PC3
|
||||||
|
|
||||||
#define RIGHT_ENC_PIN_A PD2
|
#define RIGHT_ENC_PIN_A PD2
|
||||||
#define RIGHT_ENC_PIN_B PD3
|
#define RIGHT_ENC_PIN_B PD3
|
||||||
|
@ -6,7 +6,7 @@
|
|||||||
static uint8_t enc_last=0;
|
static uint8_t enc_last=0;
|
||||||
|
|
||||||
enc_last <<=2;
|
enc_last <<=2;
|
||||||
enc_last |= (PINC & (3 << 4)) >> 4;
|
enc_last |= (PINC & (3 << 2)) >> 2;
|
||||||
|
|
||||||
left_enc_pos += ENC_STATES[(enc_last & 0x0f)];
|
left_enc_pos += ENC_STATES[(enc_last & 0x0f)];
|
||||||
}
|
}
|
||||||
|
Loading…
x
Reference in New Issue
Block a user